diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS
index 297ce75c5c176..a31fa690b3b68 100644
--- a/.github/CODEOWNERS
+++ b/.github/CODEOWNERS
@@ -248,7 +248,7 @@ tools/reaction_analyzer/** berkay@leodrive.ai
vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp
vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp
vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp
-vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp
+vehicle/autoware_raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp
vehicle/vehicle_info_util/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
### Copied from .github/CODEOWNERS-manual ###
diff --git a/launch/tier4_vehicle_launch/launch/vehicle.launch.xml b/launch/tier4_vehicle_launch/launch/vehicle.launch.xml
index 0e1d22bfd1827..67fae5722920a 100644
--- a/launch/tier4_vehicle_launch/launch/vehicle.launch.xml
+++ b/launch/tier4_vehicle_launch/launch/vehicle.launch.xml
@@ -6,7 +6,7 @@
-
+
@@ -22,7 +22,7 @@
-
+
diff --git a/vehicle/accel_brake_map_calibrator/README.md b/vehicle/accel_brake_map_calibrator/README.md
index c8813280c04ff..c2516eed5de3d 100644
--- a/vehicle/accel_brake_map_calibrator/README.md
+++ b/vehicle/accel_brake_map_calibrator/README.md
@@ -1,6 +1,6 @@
# accel_brake_map_calibrator
-The role of this node is to automatically calibrate `accel_map.csv` / `brake_map.csv` used in the `raw_vehicle_cmd_converter` node.
+The role of this node is to automatically calibrate `accel_map.csv` / `brake_map.csv` used in the `autoware_raw_vehicle_cmd_converter` node.
The base map, which is lexus's one by default, is updated iteratively with the loaded driving data.
@@ -134,15 +134,15 @@ You can also save accel and brake map in the default directory where Autoware re
## System Parameters
-| Name | Type | Description | Default value |
-| :----------------------- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------------------------------------------------- |
-| update_method | string | you can select map calibration method. "update_offset_each_cell" calculates offsets for each grid cells on the map. "update_offset_total" calculates the total offset of the map. | "update_offset_each_cell" |
-| get_pitch_method | string | "tf": get pitch from tf, "none": unable to perform pitch validation and pitch compensation | "tf" |
-| pedal_accel_graph_output | bool | if true, it will output a log of the pedal accel graph. | true |
-| progress_file_output | bool | if true, it will output a log and csv file of the update process. | false |
-| default_map_dir | str | directory of default map | [directory of *raw_vehicle_cmd_converter*]/data/default/ |
-| calibrated_map_dir | str | directory of calibrated map | [directory of *accel_brake_map_calibrator*]/config/ |
-| update_hz | double | hz for update | 10.0 |
+| Name | Type | Description | Default value |
+| :----------------------- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------------- |
+| update_method | string | you can select map calibration method. "update_offset_each_cell" calculates offsets for each grid cells on the map. "update_offset_total" calculates the total offset of the map. | "update_offset_each_cell" |
+| get_pitch_method | string | "tf": get pitch from tf, "none": unable to perform pitch validation and pitch compensation | "tf" |
+| pedal_accel_graph_output | bool | if true, it will output a log of the pedal accel graph. | true |
+| progress_file_output | bool | if true, it will output a log and csv file of the update process. | false |
+| default_map_dir | str | directory of default map | [directory of *autoware_raw_vehicle_cmd_converter*]/data/default/ |
+| calibrated_map_dir | str | directory of calibrated map | [directory of *accel_brake_map_calibrator*]/config/ |
+| update_hz | double | hz for update | 10.0 |
## Algorithm Parameters
diff --git a/vehicle/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp b/vehicle/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp
index 6b94b7301540c..baf40fafc94b5 100644
--- a/vehicle/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp
+++ b/vehicle/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp
@@ -17,9 +17,9 @@
#ifndef ACCEL_BRAKE_MAP_CALIBRATOR__ACCEL_BRAKE_MAP_CALIBRATOR_NODE_HPP_
#define ACCEL_BRAKE_MAP_CALIBRATOR__ACCEL_BRAKE_MAP_CALIBRATOR_NODE_HPP_
+#include "autoware_raw_vehicle_cmd_converter/accel_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/brake_map.hpp"
#include "diagnostic_updater/diagnostic_updater.hpp"
-#include "raw_vehicle_cmd_converter/accel_map.hpp"
-#include "raw_vehicle_cmd_converter/brake_map.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
@@ -56,12 +56,12 @@
namespace accel_brake_map_calibrator
{
+using autoware_raw_vehicle_cmd_converter::AccelMap;
+using autoware_raw_vehicle_cmd_converter::BrakeMap;
using autoware_vehicle_msgs::msg::SteeringReport;
using autoware_vehicle_msgs::msg::VelocityReport;
using geometry_msgs::msg::TwistStamped;
using nav_msgs::msg::OccupancyGrid;
-using raw_vehicle_cmd_converter::AccelMap;
-using raw_vehicle_cmd_converter::BrakeMap;
using std_msgs::msg::Float32MultiArray;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using tier4_debug_msgs::msg::Float32Stamped;
diff --git a/vehicle/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml b/vehicle/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml
index c664158a471a7..37ee49fe3c4e0 100644
--- a/vehicle/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml
+++ b/vehicle/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml
@@ -1,7 +1,7 @@
-
+
diff --git a/vehicle/accel_brake_map_calibrator/package.xml b/vehicle/accel_brake_map_calibrator/package.xml
index 4c4eadea5e1ce..0fb299b199742 100644
--- a/vehicle/accel_brake_map_calibrator/package.xml
+++ b/vehicle/accel_brake_map_calibrator/package.xml
@@ -13,11 +13,11 @@
ament_cmake_auto
autoware_cmake
+ autoware_raw_vehicle_cmd_converter
autoware_vehicle_msgs
diagnostic_updater
geometry_msgs
motion_utils
- raw_vehicle_cmd_converter
rclcpp
std_msgs
std_srvs
diff --git a/vehicle/accel_brake_map_calibrator/scripts/new_accel_brake_map_server.py b/vehicle/accel_brake_map_calibrator/scripts/new_accel_brake_map_server.py
index a2d82a460aed0..35bcfd09eaa38 100755
--- a/vehicle/accel_brake_map_calibrator/scripts/new_accel_brake_map_server.py
+++ b/vehicle/accel_brake_map_calibrator/scripts/new_accel_brake_map_server.py
@@ -40,7 +40,7 @@ def __init__(self):
CalibData, "/accel_brake_map_calibrator/get_data_service", self.get_data_callback
)
- default_map_path = get_package_share_directory("raw_vehicle_cmd_converter")
+ default_map_path = get_package_share_directory("autoware_raw_vehicle_cmd_converter")
self.declare_parameter(
"/accel_brake_map_calibrator/csv_default_map_dir", default_map_path + "/data/default/"
)
diff --git a/vehicle/accel_brake_map_calibrator/scripts/view_plot.py b/vehicle/accel_brake_map_calibrator/scripts/view_plot.py
index 4d713cf4848e0..8041f361be3ce 100755
--- a/vehicle/accel_brake_map_calibrator/scripts/view_plot.py
+++ b/vehicle/accel_brake_map_calibrator/scripts/view_plot.py
@@ -45,7 +45,7 @@ def __init__(self, args):
max_pedal_vel_thr = args.max_pedal_vel_thr
if default_map_dir is None:
- package_path = get_package_share_directory("raw_vehicle_cmd_converter")
+ package_path = get_package_share_directory("autoware_raw_vehicle_cmd_converter")
self.declare_parameter(
"/accel_brake_map_calibrator/csv_default_map_dir", package_path + "/data/default/"
)
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt
new file mode 100644
index 0000000000000..fc54b302512fa
--- /dev/null
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt
@@ -0,0 +1,44 @@
+cmake_minimum_required(VERSION 3.14)
+project(autoware_raw_vehicle_cmd_converter)
+
+find_package(autoware_cmake REQUIRED)
+autoware_package()
+
+ament_auto_add_library(actuation_map_converter SHARED
+ src/accel_map.cpp
+ src/brake_map.cpp
+ src/steer_map.cpp
+ src/csv_loader.cpp
+ src/pid.cpp
+)
+
+ament_auto_add_library(autoware_raw_vehicle_cmd_converter_node_component SHARED
+ src/node.cpp
+)
+
+target_link_libraries(autoware_raw_vehicle_cmd_converter_node_component actuation_map_converter)
+
+rclcpp_components_register_node(autoware_raw_vehicle_cmd_converter_node_component
+ PLUGIN "autoware::raw_vehicle_cmd_converter::RawVehicleCommandConverterNode"
+ EXECUTABLE autoware_raw_vehicle_cmd_converter_node
+)
+
+if(BUILD_TESTING)
+ set(TEST_SOURCES
+ test/test_autoware_raw_vehicle_cmd_converter.cpp
+ )
+ set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_autoware_raw_vehicle_cmd_converter)
+ ament_add_ros_isolated_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES})
+ target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter autoware_raw_vehicle_cmd_converter_node_component)
+endif()
+
+ament_auto_package(INSTALL_TO_SHARE
+ config
+ data
+ launch
+ test
+)
+
+install(PROGRAMS scripts/plot_accel_brake_map.py
+ DESTINATION lib/${PROJECT_NAME}
+)
diff --git a/vehicle/raw_vehicle_cmd_converter/README.md b/vehicle/autoware_raw_vehicle_cmd_converter/README.md
similarity index 95%
rename from vehicle/raw_vehicle_cmd_converter/README.md
rename to vehicle/autoware_raw_vehicle_cmd_converter/README.md
index 6ac1ee4666cae..593d713a43f4c 100644
--- a/vehicle/raw_vehicle_cmd_converter/README.md
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/README.md
@@ -1,4 +1,4 @@
-# raw_vehicle_cmd_converter
+# autoware_raw_vehicle_cmd_converter
## Overview
@@ -40,7 +40,7 @@ For ease of calibration and adjustments to the lookup table, an auto-calibration
## Parameters
-{{ json_to_markdown("vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json") }}
+{{ json_to_markdown("vehicle/autoware_raw_vehicle_cmd_converter/schema/autoware_raw_vehicle_cmd_converter.schema.json") }}
## Limitation
diff --git a/vehicle/raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml b/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml
similarity index 61%
rename from vehicle/raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml
rename to vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml
index bce50a0b581c7..b53b0d7622198 100644
--- a/vehicle/raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml
@@ -1,8 +1,8 @@
/**:
ros__parameters:
- csv_path_accel_map: $(find-pkg-share raw_vehicle_cmd_converter)/data/default/accel_map.csv
- csv_path_brake_map: $(find-pkg-share raw_vehicle_cmd_converter)/data/default/brake_map.csv
- csv_path_steer_map: $(find-pkg-share raw_vehicle_cmd_converter)/data/default/steer_map.csv
+ csv_path_accel_map: $(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/accel_map.csv
+ csv_path_brake_map: $(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/brake_map.csv
+ csv_path_steer_map: $(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/steer_map.csv
convert_accel_cmd: true
convert_brake_cmd: true
convert_steer_cmd: true
diff --git a/vehicle/raw_vehicle_cmd_converter/data/default/accel_map.csv b/vehicle/autoware_raw_vehicle_cmd_converter/data/default/accel_map.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/data/default/accel_map.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/data/default/accel_map.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/data/default/brake_map.csv b/vehicle/autoware_raw_vehicle_cmd_converter/data/default/brake_map.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/data/default/brake_map.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/data/default/brake_map.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/data/default/steer_map.csv b/vehicle/autoware_raw_vehicle_cmd_converter/data/default/steer_map.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/data/default/steer_map.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/data/default/steer_map.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/figure/accel-brake-map-table.png b/vehicle/autoware_raw_vehicle_cmd_converter/figure/accel-brake-map-table.png
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/figure/accel-brake-map-table.png
rename to vehicle/autoware_raw_vehicle_cmd_converter/figure/accel-brake-map-table.png
diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/accel_map.hpp
similarity index 75%
rename from vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/accel_map.hpp
index 3bdb71a11f744..90cc4d15fd33e 100644
--- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/accel_map.hpp
@@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef RAW_VEHICLE_CMD_CONVERTER__ACCEL_MAP_HPP_
-#define RAW_VEHICLE_CMD_CONVERTER__ACCEL_MAP_HPP_
+#ifndef AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__ACCEL_MAP_HPP_
+#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__ACCEL_MAP_HPP_
-#include "raw_vehicle_cmd_converter/csv_loader.hpp"
+#include "autoware_raw_vehicle_cmd_converter/csv_loader.hpp"
#include
@@ -24,7 +24,7 @@
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
class AccelMap
{
@@ -37,13 +37,14 @@ class AccelMap
std::vector> getAccelMap() const { return accel_map_; }
private:
- rclcpp::Logger logger_{rclcpp::get_logger("raw_vehicle_cmd_converter").get_child("accel_map")};
+ rclcpp::Logger logger_{
+ rclcpp::get_logger("autoware_raw_vehicle_cmd_converter").get_child("accel_map")};
rclcpp::Clock clock_{RCL_ROS_TIME};
std::string vehicle_name_;
std::vector vel_index_;
std::vector throttle_index_;
std::vector> accel_map_;
};
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
-#endif // RAW_VEHICLE_CMD_CONVERTER__ACCEL_MAP_HPP_
+#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__ACCEL_MAP_HPP_
diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/brake_map.hpp
similarity index 75%
rename from vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/brake_map.hpp
index 6dd5ab94c5d06..dfc5e99bfa988 100644
--- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/brake_map.hpp
@@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef RAW_VEHICLE_CMD_CONVERTER__BRAKE_MAP_HPP_
-#define RAW_VEHICLE_CMD_CONVERTER__BRAKE_MAP_HPP_
+#ifndef AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__BRAKE_MAP_HPP_
+#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__BRAKE_MAP_HPP_
-#include "raw_vehicle_cmd_converter/csv_loader.hpp"
+#include "autoware_raw_vehicle_cmd_converter/csv_loader.hpp"
#include
@@ -24,7 +24,7 @@
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
class BrakeMap
{
@@ -37,7 +37,8 @@ class BrakeMap
std::vector> getBrakeMap() const { return brake_map_; }
private:
- rclcpp::Logger logger_{rclcpp::get_logger("raw_vehicle_cmd_converter").get_child("accel_map")};
+ rclcpp::Logger logger_{
+ rclcpp::get_logger("autoware_raw_vehicle_cmd_converter").get_child("accel_map")};
rclcpp::Clock clock_{RCL_ROS_TIME};
std::string vehicle_name_;
std::vector vel_index_;
@@ -45,6 +46,6 @@ class BrakeMap
std::vector brake_index_rev_;
std::vector> brake_map_;
};
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
-#endif // RAW_VEHICLE_CMD_CONVERTER__BRAKE_MAP_HPP_
+#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__BRAKE_MAP_HPP_
diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/csv_loader.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/csv_loader.hpp
similarity index 83%
rename from vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/csv_loader.hpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/csv_loader.hpp
index ee89e03780b0b..44ba5ac571242 100644
--- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/csv_loader.hpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/csv_loader.hpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef RAW_VEHICLE_CMD_CONVERTER__CSV_LOADER_HPP_
-#define RAW_VEHICLE_CMD_CONVERTER__CSV_LOADER_HPP_
+#ifndef AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__CSV_LOADER_HPP_
+#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__CSV_LOADER_HPP_
#include
#include
@@ -21,7 +21,7 @@
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
using Table = std::vector>;
using Map = std::vector>;
@@ -42,6 +42,6 @@ class CSVLoader
private:
std::string csv_path_;
};
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
-#endif // RAW_VEHICLE_CMD_CONVERTER__CSV_LOADER_HPP_
+#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__CSV_LOADER_HPP_
diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp
similarity index 89%
rename from vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp
index d71ff96abade0..9b64c26770e40 100644
--- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp
@@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
-#define RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
+#ifndef AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
+#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
-#include "raw_vehicle_cmd_converter/accel_map.hpp"
-#include "raw_vehicle_cmd_converter/brake_map.hpp"
-#include "raw_vehicle_cmd_converter/pid.hpp"
-#include "raw_vehicle_cmd_converter/steer_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/accel_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/brake_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/pid.hpp"
+#include "autoware_raw_vehicle_cmd_converter/steer_map.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include
@@ -34,7 +34,7 @@
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
using Control = autoware_control_msgs::msg::Control;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
@@ -119,6 +119,6 @@ class RawVehicleCommandConverterNode : public rclcpp::Node
std::unique_ptr logger_configure_;
};
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
-#endif // RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
+#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/pid.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/pid.hpp
similarity index 88%
rename from vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/pid.hpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/pid.hpp
index c13de9b332fa3..a20e8d80984b5 100644
--- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/pid.hpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/pid.hpp
@@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef RAW_VEHICLE_CMD_CONVERTER__PID_HPP_
-#define RAW_VEHICLE_CMD_CONVERTER__PID_HPP_
+#ifndef AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__PID_HPP_
+#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__PID_HPP_
#include
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
class PIDController
{
@@ -60,6 +60,6 @@ class PIDController
double invalid_integration_decay_{0.0};
double is_initialized_{false};
};
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
-#endif // RAW_VEHICLE_CMD_CONVERTER__PID_HPP_
+#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__PID_HPP_
diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_map.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/steer_map.hpp
similarity index 67%
rename from vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_map.hpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/steer_map.hpp
index 7e4a3084d0223..d41bb676ffb47 100644
--- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_map.hpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/steer_map.hpp
@@ -12,18 +12,18 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_
-#define RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_
+#ifndef AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_
+#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_
-#include "raw_vehicle_cmd_converter/csv_loader.hpp"
-#include "raw_vehicle_cmd_converter/pid.hpp"
+#include "autoware_raw_vehicle_cmd_converter/csv_loader.hpp"
+#include "autoware_raw_vehicle_cmd_converter/pid.hpp"
#include
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
class SteerMap
{
@@ -36,8 +36,9 @@ class SteerMap
std::vector steer_index_;
std::vector output_index_;
std::vector> steer_map_;
- rclcpp::Logger logger_{rclcpp::get_logger("raw_vehicle_cmd_converter").get_child("steer_map")};
+ rclcpp::Logger logger_{
+ rclcpp::get_logger("autoware_raw_vehicle_cmd_converter").get_child("steer_map")};
};
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
-#endif // RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_
+#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_
diff --git a/vehicle/raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml b/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml
similarity index 70%
rename from vehicle/raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml
rename to vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml
index 0a9962a7c2a30..85553223ba1ab 100644
--- a/vehicle/raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml
@@ -5,9 +5,9 @@
-
+
-
+
diff --git a/vehicle/raw_vehicle_cmd_converter/package.xml b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml
similarity index 91%
rename from vehicle/raw_vehicle_cmd_converter/package.xml
rename to vehicle/autoware_raw_vehicle_cmd_converter/package.xml
index 376a5c74f1cb6..25a329be3a6b9 100644
--- a/vehicle/raw_vehicle_cmd_converter/package.xml
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml
@@ -1,9 +1,9 @@
- raw_vehicle_cmd_converter
+ autoware_raw_vehicle_cmd_converter
0.1.0
- The raw_vehicle_cmd_converter package
+ The autoware_raw_vehicle_cmd_converter package
Takamasa Horibe
Tanaka Taiki
Makoto Kurihara
diff --git a/vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json b/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json
similarity index 92%
rename from vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json
rename to vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json
index 4b562f401e09b..1903f8252d656 100644
--- a/vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json
@@ -3,23 +3,23 @@
"title": "Parameters for Raw Vehicle Cmd Converter",
"type": "object",
"definitions": {
- "raw_vehicle_cmd_converter": {
+ "autoware_raw_vehicle_cmd_converter": {
"type": "object",
"properties": {
"csv_path_accel_map": {
"type": "string",
"description": "path for acceleration map csv file",
- "default": "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/accel_map.csv"
+ "default": "$(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/accel_map.csv"
},
"csv_path_brake_map": {
"type": "string",
"description": "path for brake map csv file",
- "default": "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/brake_map.csv"
+ "default": "$(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/brake_map.csv"
},
"csv_path_steer_map": {
"type": "string",
"description": "path for steer map csv file",
- "default": "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/steer_map.csv"
+ "default": "$(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/steer_map.csv"
},
"convert_accel_cmd": {
"type": "boolean",
@@ -178,7 +178,7 @@
"type": "object",
"properties": {
"ros__parameters": {
- "$ref": "#/definitions/raw_vehicle_cmd_converter"
+ "$ref": "#/definitions/autoware_raw_vehicle_cmd_converter"
}
},
"required": ["ros__parameters"]
diff --git a/vehicle/raw_vehicle_cmd_converter/scripts/plot_accel_brake_map.py b/vehicle/autoware_raw_vehicle_cmd_converter/scripts/plot_accel_brake_map.py
similarity index 97%
rename from vehicle/raw_vehicle_cmd_converter/scripts/plot_accel_brake_map.py
rename to vehicle/autoware_raw_vehicle_cmd_converter/scripts/plot_accel_brake_map.py
index 62979fce89bcf..95b2271239f8f 100755
--- a/vehicle/raw_vehicle_cmd_converter/scripts/plot_accel_brake_map.py
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/scripts/plot_accel_brake_map.py
@@ -23,7 +23,7 @@
def main(dimension, map_dir, accel_or_brake):
if map_dir is None:
- script_dir = get_package_share_directory("raw_vehicle_cmd_converter")
+ script_dir = get_package_share_directory("autoware_raw_vehicle_cmd_converter")
csv_dir = script_dir + "/data/default"
else:
csv_dir = map_dir
diff --git a/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/accel_map.cpp
similarity index 95%
rename from vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/src/accel_map.cpp
index 42c63b152e4f4..236aa7dc451c3 100644
--- a/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/accel_map.cpp
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "raw_vehicle_cmd_converter/accel_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/accel_map.hpp"
#include "interpolation/linear_interpolation.hpp"
@@ -23,7 +23,7 @@
using namespace std::literals::chrono_literals;
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
bool AccelMap::readAccelMapFromCSV(const std::string & csv_path, const bool validation)
{
@@ -83,4 +83,4 @@ bool AccelMap::getAcceleration(const double throttle, const double vel, double &
return true;
}
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
diff --git a/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/brake_map.cpp
similarity index 95%
rename from vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/src/brake_map.cpp
index 68d89474f3ca6..ae0f8e5f41b1c 100644
--- a/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/brake_map.cpp
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "raw_vehicle_cmd_converter/brake_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/brake_map.hpp"
#include "interpolation/linear_interpolation.hpp"
@@ -20,7 +20,7 @@
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
bool BrakeMap::readBrakeMapFromCSV(const std::string & csv_path, const bool validation)
{
@@ -94,4 +94,4 @@ bool BrakeMap::getAcceleration(const double brake, const double vel, double & ac
return true;
}
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
diff --git a/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/csv_loader.cpp
similarity index 96%
rename from vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/src/csv_loader.cpp
index a6a331a0e7324..8044a88bc9898 100644
--- a/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/csv_loader.cpp
@@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "raw_vehicle_cmd_converter/csv_loader.hpp"
+#include "autoware_raw_vehicle_cmd_converter/csv_loader.hpp"
#include
#include
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
CSVLoader::CSVLoader(const std::string & csv_path)
{
@@ -150,4 +150,4 @@ double CSVLoader::clampValue(
return val;
}
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
diff --git a/vehicle/raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp
similarity index 96%
rename from vehicle/raw_vehicle_cmd_converter/src/node.cpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp
index 91c668f63dfbd..9a28739f9f218 100644
--- a/vehicle/raw_vehicle_cmd_converter/src/node.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp
@@ -12,18 +12,18 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "raw_vehicle_cmd_converter/node.hpp"
+#include "autoware_raw_vehicle_cmd_converter/node.hpp"
#include
#include
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
const rclcpp::NodeOptions & node_options)
-: Node("raw_vehicle_cmd_converter_node", node_options)
+: Node("autoware_raw_vehicle_cmd_converter_node", node_options)
{
using std::placeholders::_1;
/* parameters for accel/brake map */
@@ -83,7 +83,7 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
sub_steering_ = create_subscription(
"~/input/steering", 1, std::bind(&RawVehicleCommandConverterNode::onSteering, this, _1));
debug_pub_steer_pid_ = create_publisher(
- "/vehicle/raw_vehicle_cmd_converter/debug/steer_pid", 1);
+ "/vehicle/autoware_raw_vehicle_cmd_converter/debug/steer_pid", 1);
logger_configure_ = std::make_unique(this);
}
@@ -221,7 +221,7 @@ void RawVehicleCommandConverterNode::onControlCmd(const Control::ConstSharedPtr
control_cmd_ptr_ = msg;
publishActuationCmd();
}
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(raw_vehicle_cmd_converter::RawVehicleCommandConverterNode)
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::raw_vehicle_cmd_converter::RawVehicleCommandConverterNode)
diff --git a/vehicle/raw_vehicle_cmd_converter/src/pid.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/pid.cpp
similarity index 95%
rename from vehicle/raw_vehicle_cmd_converter/src/pid.cpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/src/pid.cpp
index 216382be3dc81..ebc608cd61fad 100644
--- a/vehicle/raw_vehicle_cmd_converter/src/pid.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/pid.cpp
@@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "raw_vehicle_cmd_converter/pid.hpp"
+#include "autoware_raw_vehicle_cmd_converter/pid.hpp"
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
double PIDController::calculateFB(
@@ -100,4 +100,4 @@ void PIDController::reset()
prev_error_ = 0;
is_first_time_ = true;
}
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
diff --git a/vehicle/raw_vehicle_cmd_converter/src/steer_map.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/steer_map.cpp
similarity index 91%
rename from vehicle/raw_vehicle_cmd_converter/src/steer_map.cpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/src/steer_map.cpp
index e050a1beba3ae..6abe8adfdc9e3 100644
--- a/vehicle/raw_vehicle_cmd_converter/src/steer_map.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/steer_map.cpp
@@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "raw_vehicle_cmd_converter/steer_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/steer_map.hpp"
#include "interpolation/linear_interpolation.hpp"
#include
#include
-namespace raw_vehicle_cmd_converter
+namespace autoware::raw_vehicle_cmd_converter
{
bool SteerMap::readSteerMapFromCSV(const std::string & csv_path, const bool validation)
@@ -53,4 +53,4 @@ void SteerMap::getSteer(const double steer_rate, const double steer, double & ou
CSVLoader::clampValue(steer_rate, steer_rate_interp, "steer: steer_rate");
output = interpolation::lerp(steer_rate_interp, output_index_, clamped_steer_rate);
}
-} // namespace raw_vehicle_cmd_converter
+} // namespace autoware::raw_vehicle_cmd_converter
diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_1col_map.csv b/vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_1col_map.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/test/map_data/test_1col_map.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_1col_map.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_accel_map.csv b/vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_accel_map.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/test/map_data/test_accel_map.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_accel_map.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_brake_map.csv b/vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_brake_map.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/test/map_data/test_brake_map.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_brake_map.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_inconsistent_rows_map.csv b/vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_inconsistent_rows_map.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/test/map_data/test_inconsistent_rows_map.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_inconsistent_rows_map.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_not_interpolatable.csv b/vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_not_interpolatable.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/test/map_data/test_not_interpolatable.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_not_interpolatable.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_steer_map.csv b/vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_steer_map.csv
similarity index 100%
rename from vehicle/raw_vehicle_cmd_converter/test/map_data/test_steer_map.csv
rename to vehicle/autoware_raw_vehicle_cmd_converter/test/map_data/test_steer_map.csv
diff --git a/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp
similarity index 92%
rename from vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp
rename to vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp
index 9f035b303e1a9..746f872789b07 100644
--- a/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp
@@ -13,11 +13,11 @@
// limitations under the License.
#include "ament_index_cpp/get_package_share_directory.hpp"
+#include "autoware_raw_vehicle_cmd_converter/accel_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/brake_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/pid.hpp"
+#include "autoware_raw_vehicle_cmd_converter/steer_map.hpp"
#include "gtest/gtest.h"
-#include "raw_vehicle_cmd_converter/accel_map.hpp"
-#include "raw_vehicle_cmd_converter/brake_map.hpp"
-#include "raw_vehicle_cmd_converter/pid.hpp"
-#include "raw_vehicle_cmd_converter/steer_map.hpp"
#include
#include
@@ -48,14 +48,15 @@
*
*/
-using raw_vehicle_cmd_converter::AccelMap;
-using raw_vehicle_cmd_converter::BrakeMap;
-using raw_vehicle_cmd_converter::PIDController;
-using raw_vehicle_cmd_converter::SteerMap;
+using autoware::raw_vehicle_cmd_converter::AccelMap;
+using autoware::raw_vehicle_cmd_converter::BrakeMap;
+using autoware::raw_vehicle_cmd_converter::PIDController;
+using autoware::raw_vehicle_cmd_converter::SteerMap;
double epsilon = 1e-4;
// may throw PackageNotFoundError exception for invalid package
const auto map_path =
- ament_index_cpp::get_package_share_directory("raw_vehicle_cmd_converter") + "/test/map_data/";
+ ament_index_cpp::get_package_share_directory("autoware_raw_vehicle_cmd_converter") +
+ "/test/map_data/";
bool loadAccelMapData(AccelMap & accel_map)
{
@@ -93,7 +94,8 @@ TEST(ConverterTests, LoadExampleMap)
BrakeMap brake_map;
SteerMap steer_map;
const auto data_path =
- ament_index_cpp::get_package_share_directory("raw_vehicle_cmd_converter") + "/data/default/";
+ ament_index_cpp::get_package_share_directory("autoware_raw_vehicle_cmd_converter") +
+ "/data/default/";
// for invalid path
EXPECT_TRUE(accel_map.readAccelMapFromCSV(data_path + "accel_map.csv", true));
EXPECT_TRUE(brake_map.readBrakeMapFromCSV(data_path + "brake_map.csv", true));
diff --git a/vehicle/external_cmd_converter/include/external_cmd_converter/node.hpp b/vehicle/external_cmd_converter/include/external_cmd_converter/node.hpp
index 2488c8ea7f300..c8b33fb0dc032 100644
--- a/vehicle/external_cmd_converter/include/external_cmd_converter/node.hpp
+++ b/vehicle/external_cmd_converter/include/external_cmd_converter/node.hpp
@@ -15,9 +15,9 @@
#ifndef EXTERNAL_CMD_CONVERTER__NODE_HPP_
#define EXTERNAL_CMD_CONVERTER__NODE_HPP_
+#include
+#include
#include
-#include
-#include
#include
#include
@@ -36,8 +36,8 @@ using GearCommand = autoware_vehicle_msgs::msg::GearCommand;
using Control = autoware_control_msgs::msg::Control;
using ExternalControlCommand = tier4_external_api_msgs::msg::ControlCommandStamped;
using Odometry = nav_msgs::msg::Odometry;
-using raw_vehicle_cmd_converter::AccelMap;
-using raw_vehicle_cmd_converter::BrakeMap;
+using autoware_raw_vehicle_cmd_converter::AccelMap;
+using autoware_raw_vehicle_cmd_converter::BrakeMap;
using Odometry = nav_msgs::msg::Odometry;
class ExternalCmdConverterNode : public rclcpp::Node
diff --git a/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.py b/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.py
index 77dbb99d9b477..e3f5ec20e6165 100644
--- a/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.py
+++ b/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.py
@@ -33,7 +33,7 @@ def generate_launch_description():
DeclareLaunchArgument(
"csv_path_accel_map",
default_value=[
- FindPackageShare("raw_vehicle_cmd_converter"),
+ FindPackageShare("autoware_raw_vehicle_cmd_converter"),
"/data/default/accel_map.csv",
], # noqa: E501
description="csv file path for accel map",
@@ -41,7 +41,7 @@ def generate_launch_description():
DeclareLaunchArgument(
"csv_path_brake_map",
default_value=[
- FindPackageShare("raw_vehicle_cmd_converter"),
+ FindPackageShare("autoware_raw_vehicle_cmd_converter"),
"/data/default/brake_map.csv",
], # noqa: E501
description="csv file path for brake map",
diff --git a/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml b/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml
index 856b534af81da..b2ac46297b044 100644
--- a/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml
+++ b/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml
@@ -2,8 +2,8 @@
-
-
+
+
diff --git a/vehicle/external_cmd_converter/package.xml b/vehicle/external_cmd_converter/package.xml
index 513d73d2d39ff..8c8617daa09aa 100644
--- a/vehicle/external_cmd_converter/package.xml
+++ b/vehicle/external_cmd_converter/package.xml
@@ -13,11 +13,11 @@
autoware_cmake
autoware_control_msgs
+ autoware_raw_vehicle_cmd_converter
autoware_vehicle_msgs
diagnostic_updater
geometry_msgs
nav_msgs
- raw_vehicle_cmd_converter
rclcpp
rclcpp_components
std_msgs
diff --git a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt
deleted file mode 100644
index d253b2315465e..0000000000000
--- a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt
+++ /dev/null
@@ -1,44 +0,0 @@
-cmake_minimum_required(VERSION 3.14)
-project(raw_vehicle_cmd_converter)
-
-find_package(autoware_cmake REQUIRED)
-autoware_package()
-
-ament_auto_add_library(actuation_map_converter SHARED
- src/accel_map.cpp
- src/brake_map.cpp
- src/steer_map.cpp
- src/csv_loader.cpp
- src/pid.cpp
-)
-
-ament_auto_add_library(raw_vehicle_cmd_converter_node_component SHARED
- src/node.cpp
-)
-
-target_link_libraries(raw_vehicle_cmd_converter_node_component actuation_map_converter)
-
-rclcpp_components_register_node(raw_vehicle_cmd_converter_node_component
- PLUGIN "raw_vehicle_cmd_converter::RawVehicleCommandConverterNode"
- EXECUTABLE raw_vehicle_cmd_converter_node
-)
-
-if(BUILD_TESTING)
- set(TEST_SOURCES
- test/test_raw_vehicle_cmd_converter.cpp
- )
- set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_raw_vehicle_cmd_converter)
- ament_add_ros_isolated_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES})
- target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter raw_vehicle_cmd_converter_node_component)
-endif()
-
-ament_auto_package(INSTALL_TO_SHARE
- config
- data
- launch
- test
-)
-
-install(PROGRAMS scripts/plot_accel_brake_map.py
- DESTINATION lib/${PROJECT_NAME}
-)