Skip to content

Commit

Permalink
chore(vehicle_cmd_gate): add prefix autoware_ to vehicle_cmd_gate (#7327
Browse files Browse the repository at this point in the history
)

* add prefix autoware_ to vehicle_cmd_gate package

Signed-off-by: Go Sakayori <[email protected]>

* fix

Signed-off-by: Go Sakayori <[email protected]>

* fix include guard

Signed-off-by: Go Sakayori <[email protected]>

* fix pre-commit

Signed-off-by: Go Sakayori <[email protected]>

---------

Signed-off-by: Go Sakayori <[email protected]>
Signed-off-by: Go Sakayori <[email protected]>
  • Loading branch information
go-sakayori authored Jun 10, 2024
1 parent 09f7676 commit a137560
Show file tree
Hide file tree
Showing 24 changed files with 40 additions and 40 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ control/shift_decider/** [email protected]
control/autoware_smart_mpc_trajectory_follower/** [email protected]
control/trajectory_follower_base/** [email protected] [email protected]
control/trajectory_follower_node/** [email protected] [email protected]
control/vehicle_cmd_gate/** [email protected] [email protected]
control/autoware_vehicle_cmd_gate/** [email protected] [email protected]
evaluator/control_evaluator/** [email protected] [email protected]
evaluator/diagnostic_converter/** [email protected] [email protected] [email protected]
evaluator/kinematic_evaluator/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.5)
project(vehicle_cmd_gate)
project(autoware_vehicle_cmd_gate)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -12,7 +12,7 @@ ament_auto_add_library(vehicle_cmd_gate_node SHARED
)

rclcpp_components_register_node(vehicle_cmd_gate_node
PLUGIN "vehicle_cmd_gate::VehicleCmdGate"
PLUGIN "autoware::vehicle_cmd_gate::VehicleCmdGate"
EXECUTABLE vehicle_cmd_gate_exe
)

Expand Down
File renamed without changes.
File renamed without changes
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
<launch>
<arg name="config_file" default="$(find-pkg-share vehicle_cmd_gate)/config/vehicle_cmd_gate.param.yaml"/>
<arg name="config_file" default="$(find-pkg-share autoware_vehicle_cmd_gate)/config/vehicle_cmd_gate.param.yaml"/>
<arg name="check_external_emergency_heartbeat" default="true"/>

<!-- vehicle info -->
<arg name="vehicle_info_param_file" default="$(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml"/>

<node pkg="vehicle_cmd_gate" exec="vehicle_cmd_gate_exe" name="vehicle_cmd_gate" output="screen">
<node pkg="autoware_vehicle_cmd_gate" exec="vehicle_cmd_gate_exe" name="vehicle_cmd_gate" output="screen">
<remap from="input/steering" to="/vehicle/status/steering_status"/>

<remap from="input/auto/control_cmd" to="trajectory_follower/control_cmd"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>vehicle_cmd_gate</name>
<name>autoware_vehicle_cmd_gate</name>
<version>0.1.0</version>
<description>The vehicle_cmd_gate package</description>
<maintainer email="[email protected]">Takamasa Horibe</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "adapi_pause_interface.hpp"

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{

AdapiPauseInterface::AdapiPauseInterface(rclcpp::Node * node) : node_(node)
Expand Down Expand Up @@ -65,4 +65,4 @@ void AdapiPauseInterface::on_pause(
res->status.success = true;
}

} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <autoware_control_msgs/msg/control.hpp>

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{

class AdapiPauseInterface
Expand Down Expand Up @@ -55,6 +55,6 @@ class AdapiPauseInterface
const SetPause::Service::Response::SharedPtr res);
};

} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate

#endif // ADAPI_PAUSE_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <string>

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{
inline geometry_msgs::msg::Point createMarkerPosition(double x, double y, double z)
{
Expand Down Expand Up @@ -114,6 +114,6 @@ inline void appendMarkerArray(
marker_array->markers.push_back(marker);
}
}
} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate

#endif // MARKER_HELPER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "moderate_stop_interface.hpp"

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{

ModerateStopInterface::ModerateStopInterface(rclcpp::Node * node) : node_(node)
Expand Down Expand Up @@ -66,4 +66,4 @@ void ModerateStopInterface::update_stop_state()
}
}

} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <string>
#include <unordered_map>

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{

class ModerateStopInterface
Expand Down Expand Up @@ -53,6 +53,6 @@ class ModerateStopInterface
void update_stop_state();
};

} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate

#endif // MODERATE_STOP_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include <algorithm>
#include <cmath>

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{

VehicleCmdFilter::VehicleCmdFilter()
Expand Down Expand Up @@ -319,4 +319,4 @@ double VehicleCmdFilter::getSteerDiffLim() const
return interpolateFromSpeed(param_.actual_steer_diff_lim);
}

} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,17 @@
#ifndef VEHICLE_CMD_FILTER_HPP_
#define VEHICLE_CMD_FILTER_HPP_

#include <autoware_vehicle_cmd_gate/msg/is_filter_activated.hpp>
#include <rclcpp/rclcpp.hpp>
#include <vehicle_cmd_gate/msg/is_filter_activated.hpp>

#include <autoware_control_msgs/msg/control.hpp>

#include <vector>

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{
using autoware_control_msgs::msg::Control;
using vehicle_cmd_gate::msg::IsFilterActivated;
using autoware_vehicle_cmd_gate::msg::IsFilterActivated;
using LimitArray = std::vector<double>;

struct VehicleCmdFilterParam
Expand Down Expand Up @@ -98,6 +98,6 @@ class VehicleCmdFilter
double getSteerRateLim() const;
double getSteerDiffLim() const;
};
} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate

#endif // VEHICLE_CMD_FILTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include <utility>
#include <vector>

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{

namespace
Expand Down Expand Up @@ -906,7 +906,7 @@ void VehicleCmdGate::publishMarkers(const IsFilterActivated & filter_activated)
filter_activated_flag_pub_->publish(filter_activated_flag);
filter_activated_marker_raw_pub_->publish(createMarkerArray(filter_activated));
}
} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(vehicle_cmd_gate::VehicleCmdGate)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::vehicle_cmd_gate::VehicleCmdGate)
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,11 @@
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "vehicle_cmd_filter.hpp"

#include <autoware_vehicle_cmd_gate/msg/is_filter_activated.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <motion_utils/vehicle/vehicle_state_checker.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
#include <vehicle_cmd_gate/msg/is_filter_activated.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
Expand All @@ -51,13 +51,14 @@
#include <memory>
#include <vector>

namespace vehicle_cmd_gate
namespace autoware::vehicle_cmd_gate
{

using autoware_adapi_v1_msgs::msg::MrmState;
using autoware_adapi_v1_msgs::msg::OperationModeState;
using autoware_control_msgs::msg::Control;
using autoware_control_msgs::msg::Longitudinal;
using autoware_vehicle_cmd_gate::msg::IsFilterActivated;
using autoware_vehicle_msgs::msg::GearCommand;
using autoware_vehicle_msgs::msg::HazardLightsCommand;
using autoware_vehicle_msgs::msg::SteeringReport;
Expand All @@ -71,7 +72,6 @@ using tier4_external_api_msgs::msg::Heartbeat;
using tier4_external_api_msgs::srv::SetEmergency;
using tier4_system_msgs::msg::MrmBehaviorStatus;
using tier4_vehicle_msgs::msg::VehicleEmergencyStamped;
using vehicle_cmd_gate::msg::IsFilterActivated;
using visualization_msgs::msg::MarkerArray;

using diagnostic_msgs::msg::DiagnosticStatus;
Expand Down Expand Up @@ -257,5 +257,5 @@ class VehicleCmdGate : public rclcpp::Node
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
};

} // namespace vehicle_cmd_gate
} // namespace autoware::vehicle_cmd_gate
#endif // VEHICLE_CMD_GATE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ const std::vector<double> lat_jerk_lim = {1.7, 1.3, 0.9, 0.6};
const std::vector<double> actual_steer_diff_lim = {0.5, 0.4, 0.2, 0.1};
const double wheelbase = 2.89;

using vehicle_cmd_gate::VehicleCmdGate;
using autoware::vehicle_cmd_gate::VehicleCmdGate;

using autoware_adapi_v1_msgs::msg::MrmState;
using autoware_adapi_v1_msgs::msg::OperationModeState;
Expand Down Expand Up @@ -369,7 +369,7 @@ std::shared_ptr<VehicleCmdGate> generateNode()
auto node_options = rclcpp::NodeOptions{};

const auto vehicle_cmd_gate_dir =
ament_index_cpp::get_package_share_directory("vehicle_cmd_gate");
ament_index_cpp::get_package_share_directory("autoware_vehicle_cmd_gate");
const auto vehicle_info_util_dir =
ament_index_cpp::get_package_share_directory("vehicle_info_util");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,17 +24,17 @@
#define ASSERT_LT_NEAR(x, y) ASSERT_LT(x, y + THRESHOLD)
#define ASSERT_GT_NEAR(x, y) ASSERT_GT(x, y - THRESHOLD)

using autoware::vehicle_cmd_gate::LimitArray;
using autoware_control_msgs::msg::Control;
using vehicle_cmd_gate::LimitArray;

constexpr double NOMINAL_INTERVAL = 1.0;

void setFilterParams(
vehicle_cmd_gate::VehicleCmdFilter & f, double v, LimitArray speed_points, LimitArray a,
autoware::vehicle_cmd_gate::VehicleCmdFilter & f, double v, LimitArray speed_points, LimitArray a,
LimitArray j, LimitArray lat_a, LimitArray lat_j, LimitArray steer_diff, LimitArray steer_lim,
LimitArray steer_rate_lim, const double wheelbase)
{
vehicle_cmd_gate::VehicleCmdFilterParam p;
autoware::vehicle_cmd_gate::VehicleCmdFilterParam p;
p.vel_lim = v;
p.wheel_base = wheelbase;
p.reference_speed_points = speed_points;
Expand Down Expand Up @@ -105,7 +105,7 @@ void test_1d_limit(
const double WHEELBASE = 3.0;
const double DT = 0.1; // [s]

vehicle_cmd_gate::VehicleCmdFilter filter;
autoware::vehicle_cmd_gate::VehicleCmdFilter filter;
filter.setCurrentSpeed(ego_v);
setFilterParams(
filter, V_LIM, {0.0}, {A_LIM}, {J_LIM}, {LAT_A_LIM}, {LAT_J_LIM}, {STEER_DIFF}, {STEER_LIM},
Expand Down Expand Up @@ -275,9 +275,9 @@ TEST(VehicleCmdFilter, VehicleCmdFilter)
TEST(VehicleCmdFilter, VehicleCmdFilterInterpolate)
{
constexpr double WHEELBASE = 2.8;
vehicle_cmd_gate::VehicleCmdFilter filter;
autoware::vehicle_cmd_gate::VehicleCmdFilter filter;

vehicle_cmd_gate::VehicleCmdFilterParam p;
autoware::vehicle_cmd_gate::VehicleCmdFilterParam p;
p.wheel_base = WHEELBASE;
p.vel_lim = 20.0;
p.reference_speed_points = std::vector<double>{2.0, 4.0, 10.0};
Expand Down
4 changes: 2 additions & 2 deletions launch/tier4_control_launch/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -194,8 +194,8 @@ def launch_setup(context, *args, **kwargs):

# vehicle cmd gate
vehicle_cmd_gate_component = ComposableNode(
package="vehicle_cmd_gate",
plugin="vehicle_cmd_gate::VehicleCmdGate",
package="autoware_vehicle_cmd_gate",
plugin="autoware::vehicle_cmd_gate::VehicleCmdGate",
name="vehicle_cmd_gate",
remappings=[
("input/steering", "/vehicle/status/steering_status"),
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_control_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>autoware_lane_departure_checker</exec_depend>
<exec_depend>autoware_vehicle_cmd_gate</exec_depend>
<exec_depend>control_evaluator</exec_depend>
<exec_depend>external_cmd_converter</exec_depend>
<exec_depend>external_cmd_selector</exec_depend>
<exec_depend>shift_decider</exec_depend>
<exec_depend>trajectory_follower_node</exec_depend>
<exec_depend>vehicle_cmd_gate</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down

0 comments on commit a137560

Please sign in to comment.