Skip to content

Commit

Permalink
add prefix
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 committed Jun 8, 2024
1 parent 3b036b1 commit 2267336
Show file tree
Hide file tree
Showing 43 changed files with 166 additions and 161 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -248,7 +248,7 @@ tools/reaction_analyzer/** [email protected]
vehicle/accel_brake_map_calibrator/** [email protected] [email protected] [email protected]
vehicle/autoware_steer_offset_estimator/** [email protected]
vehicle/external_cmd_converter/** [email protected]
vehicle/raw_vehicle_cmd_converter/** [email protected] [email protected] [email protected]
vehicle/autoware_raw_vehicle_cmd_converter/** [email protected] [email protected] [email protected]
vehicle/vehicle_info_util/** [email protected] [email protected] [email protected]

### Copied from .github/CODEOWNERS-manual ###
4 changes: 2 additions & 2 deletions launch/tier4_vehicle_launch/launch/vehicle.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="vehicle_id" default="$(env VEHICLE_ID default)" description="vehicle specific ID"/>
<arg name="initial_engage_state" default="false" description="/vehicle/engage state after starting Autoware"/>
<arg name="config_dir" default="$(find-pkg-share $(var sensor_model)_description)/config" description="path to dir where sensors_calibration.yaml, etc. are located"/>
<arg name="raw_vehicle_cmd_converter_param_path" default="$(find-pkg-share raw_vehicle_cmd_converter)/config/raw_vehicle_cmd_converter.param.yaml"/>
<arg name="autoware_raw_vehicle_cmd_converter_param_path" default="$(find-pkg-share autoware_raw_vehicle_cmd_converter)/config/autoware_raw_vehicle_cmd_converter.param.yaml"/>

<let name="vehicle_launch_pkg" value="$(find-pkg-share $(var vehicle_model)_launch)"/>

Expand All @@ -22,7 +22,7 @@
<group if="$(var launch_vehicle_interface)">
<include file="$(var vehicle_launch_pkg)/launch/vehicle_interface.launch.xml">
<arg name="vehicle_id" value="$(var vehicle_id)"/>
<arg name="raw_vehicle_cmd_converter_param_path" value="$(var raw_vehicle_cmd_converter_param_path)"/>
<arg name="autoware_raw_vehicle_cmd_converter_param_path" value="$(var autoware_raw_vehicle_cmd_converter_param_path)"/>
<arg name="initial_engage_state" value="$(var initial_engage_state)"/>
</include>
</group>
Expand Down
20 changes: 10 additions & 10 deletions vehicle/accel_brake_map_calibrator/README.md
Original file line number Diff line number Diff line change
@@ -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.

Expand Down Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="accel_brake_map_calib_param" default="$(find-pkg-share accel_brake_map_calibrator)/config/accel_brake_map_calibrator.param.yaml"/>
<arg name="csv_default_map_dir" default="$(find-pkg-share raw_vehicle_cmd_converter)/data/default/"/>
<arg name="csv_default_map_dir" default="$(find-pkg-share autoware_raw_vehicle_cmd_converter)/data/default/"/>
<arg name="csv_calibrated_map_dir" default="$(find-pkg-share accel_brake_map_calibrator)/config/"/>
<arg name="logger_level" default="info"/>
<arg name="rviz" default="true"/>
Expand Down
2 changes: 1 addition & 1 deletion vehicle/accel_brake_map_calibrator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,11 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_raw_vehicle_cmd_converter</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
<depend>raw_vehicle_cmd_converter</depend>
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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/"
)
Expand Down
2 changes: 1 addition & 1 deletion vehicle/accel_brake_map_calibrator/scripts/view_plot.py
Original file line number Diff line number Diff line change
Expand Up @@ -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/"
)
Expand Down
44 changes: 44 additions & 0 deletions vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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}
)
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# raw_vehicle_cmd_converter
# autoware_raw_vehicle_cmd_converter

## Overview

Expand Down Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
@@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <rclcpp/rclcpp.hpp>

Expand All @@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace raw_vehicle_cmd_converter
namespace autoware::raw_vehicle_cmd_converter
{
class AccelMap
{
Expand All @@ -37,13 +37,14 @@ class AccelMap
std::vector<std::vector<double>> 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<double> vel_index_;
std::vector<double> throttle_index_;
std::vector<std::vector<double>> 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_
Original file line number Diff line number Diff line change
Expand Up @@ -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 <rclcpp/rclcpp.hpp>

Expand All @@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace raw_vehicle_cmd_converter
namespace autoware::raw_vehicle_cmd_converter
{
class BrakeMap
{
Expand All @@ -37,14 +37,15 @@ class BrakeMap
std::vector<std::vector<double>> 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<double> vel_index_;
std::vector<double> brake_index_;
std::vector<double> brake_index_rev_;
std::vector<std::vector<double>> 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_
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@
// 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 <fstream>
#include <iostream>
#include <sstream>
#include <string>
#include <vector>

namespace raw_vehicle_cmd_converter
namespace autoware::raw_vehicle_cmd_converter
{
using Table = std::vector<std::vector<std::string>>;
using Map = std::vector<std::vector<double>>;
Expand All @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -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 <rclcpp/rclcpp.hpp>
Expand All @@ -34,7 +34,7 @@
#include <string>
#include <vector>

namespace raw_vehicle_cmd_converter
namespace autoware::raw_vehicle_cmd_converter
{
using Control = autoware_control_msgs::msg::Control;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
Expand Down Expand Up @@ -119,6 +119,6 @@ class RawVehicleCommandConverterNode : public rclcpp::Node

std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> 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_
Original file line number Diff line number Diff line change
Expand Up @@ -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 <algorithm>
#include <iostream>
#include <vector>

namespace raw_vehicle_cmd_converter
namespace autoware::raw_vehicle_cmd_converter
{
class PIDController
{
Expand Down Expand Up @@ -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_
Loading

0 comments on commit 2267336

Please sign in to comment.