Skip to content

Commit 044667d

Browse files
committed
feat(raw_vehicle_cmd_converter): add vehicle adaptor
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 8f79195 commit 044667d

File tree

7 files changed

+120
-22
lines changed

7 files changed

+120
-22
lines changed

simulator/autoware_carla_interface/launch/autoware_carla_interface.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131

3232
<arg name="input_control_cmd" default="/control/command/control_cmd"/>
3333
<arg name="input_odometry" default="/localization/kinematic_state"/>
34+
<arg name="input_accel" default="/localization/acceleration"/>
3435
<arg name="input_steering" default="/vehicle/status/steering_status"/>
3536
<arg name="output_actuation_cmd" default="/control/command/actuation_cmd"/>
3637
<arg name="config_file" default="$(find-pkg-share autoware_carla_interface)/raw_vehicle_cmd_converter.param.yaml"/>
@@ -39,6 +40,7 @@
3940
<param from="$(var config_file)" allow_substs="true"/>
4041
<remap from="~/input/control_cmd" to="$(var input_control_cmd)"/>
4142
<remap from="~/input/odometry" to="$(var input_odometry)"/>
43+
<remap from="~/input/accel" to="$(var input_accel)"/>
4244
<remap from="~/input/steering" to="$(var input_steering)"/>
4345
<remap from="~/output/actuation_cmd" to="$(var output_actuation_cmd)"/>
4446
</node>

vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt

+6-2
Original file line numberDiff line numberDiff line change
@@ -13,11 +13,15 @@ ament_auto_add_library(actuation_map_converter SHARED
1313
src/vgr.cpp
1414
)
1515

16+
ament_auto_add_library(vehicle_adaptor SHARED
17+
src/vehicle_adaptor/vehicle_adaptor.cpp
18+
)
19+
1620
ament_auto_add_library(autoware_raw_vehicle_cmd_converter_node_component SHARED
1721
src/node.cpp
1822
)
1923

20-
target_link_libraries(autoware_raw_vehicle_cmd_converter_node_component actuation_map_converter)
24+
target_link_libraries(autoware_raw_vehicle_cmd_converter_node_component actuation_map_converter vehicle_adaptor)
2125

2226
rclcpp_components_register_node(autoware_raw_vehicle_cmd_converter_node_component
2327
PLUGIN "autoware::raw_vehicle_cmd_converter::RawVehicleCommandConverterNode"
@@ -30,7 +34,7 @@ if(BUILD_TESTING)
3034
)
3135
set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_autoware_raw_vehicle_cmd_converter)
3236
ament_add_ros_isolated_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES})
33-
target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter autoware_raw_vehicle_cmd_converter_node_component)
37+
target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter vehicle_adaptor autoware_raw_vehicle_cmd_converter_node_component)
3438
endif()
3539

3640
ament_auto_package(INSTALL_TO_SHARE

vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include "autoware_raw_vehicle_cmd_converter/brake_map.hpp"
2222
#include "autoware_raw_vehicle_cmd_converter/pid.hpp"
2323
#include "autoware_raw_vehicle_cmd_converter/steer_map.hpp"
24+
#include "autoware_raw_vehicle_cmd_converter/vehicle_adaptor/vehicle_adaptor.hpp"
2425
#include "autoware_raw_vehicle_cmd_converter/vgr.hpp"
2526

2627
#include <rclcpp/rclcpp.hpp>
@@ -46,7 +47,7 @@ using tier4_vehicle_msgs::msg::ActuationStatusStamped;
4647
using TwistStamped = geometry_msgs::msg::TwistStamped;
4748
using Odometry = nav_msgs::msg::Odometry;
4849
using Steering = autoware_vehicle_msgs::msg::SteeringReport;
49-
50+
using geometry_msgs::msg::AccelWithCovarianceStamped;
5051
class DebugValues
5152
{
5253
public:
@@ -86,17 +87,21 @@ class RawVehicleCommandConverterNode : public rclcpp::Node
8687
// polling subscribers
8788
autoware::universe_utils::InterProcessPollingSubscriber<Odometry> sub_odometry_{
8889
this, "~/input/odometry"};
90+
autoware::universe_utils::InterProcessPollingSubscriber<AccelWithCovarianceStamped> sub_accel_{
91+
this, "~/input/accel"};
8992

9093
rclcpp::TimerBase::SharedPtr timer_;
9194

9295
std::unique_ptr<TwistStamped> current_twist_ptr_; // [m/s]
9396
std::unique_ptr<double> current_steer_ptr_;
9497
ActuationStatusStamped::ConstSharedPtr actuation_status_ptr_;
98+
Odometry::ConstSharedPtr current_odometry_;
9599
Control::ConstSharedPtr control_cmd_ptr_;
96100
AccelMap accel_map_;
97101
BrakeMap brake_map_;
98102
SteerMap steer_map_;
99103
VGR vgr_;
104+
VehicleAdaptor vehicle_adaptor_;
100105
// TODO(tanaka): consider accel/brake pid too
101106
PIDController steer_pid_;
102107
bool ff_map_initialized_;
@@ -112,6 +117,7 @@ class RawVehicleCommandConverterNode : public rclcpp::Node
112117
bool convert_brake_cmd_; //!< @brief use brake or not
113118
std::optional<std::string> convert_steer_cmd_method_{std::nullopt}; //!< @brief method to convert
114119
bool need_to_subscribe_actuation_status_{false};
120+
bool use_vehicle_adaptor_{false};
115121
rclcpp::Time prev_time_steer_calculation_{0, 0, RCL_ROS_TIME};
116122

117123
// Whether to subscribe to actuation_status and calculate and publish steering_status
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
// Copyright 2024 Tier IV, Inc. All rights reserved.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VEHICLE_ADAPTOR__VEHICLE_ADAPTOR_HPP_
16+
#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VEHICLE_ADAPTOR__VEHICLE_ADAPTOR_HPP_
17+
18+
#include <autoware_control_msgs/msg/control.hpp>
19+
#include <autoware_vehicle_msgs/msg/steering_report.hpp>
20+
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
21+
#include <nav_msgs/msg/odometry.hpp>
22+
23+
namespace autoware::raw_vehicle_cmd_converter
24+
{
25+
26+
using autoware_control_msgs::msg::Control;
27+
using autoware_vehicle_msgs::msg::SteeringReport;
28+
using geometry_msgs::msg::AccelWithCovarianceStamped;
29+
using nav_msgs::msg::Odometry;
30+
31+
class VehicleAdaptor
32+
{
33+
public:
34+
VehicleAdaptor() = default;
35+
Control compensate(
36+
const Control & input_control_cmd, [[maybe_unused]] const Odometry & odometry,
37+
[[maybe_unused]] const AccelWithCovarianceStamped & accel,
38+
[[maybe_unused]] const double steering);
39+
40+
private:
41+
};
42+
} // namespace autoware::raw_vehicle_cmd_converter
43+
44+
#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VEHICLE_ADAPTOR__VEHICLE_ADAPTOR_HPP_

vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
<launch>
33
<arg name="input_control_cmd" default="/control/command/control_cmd"/>
44
<arg name="input_odometry" default="/localization/kinematic_state"/>
5+
<arg name="input_accel" default="/localization/acceleration"/>
56
<arg name="input_steering" default="/vehicle/status/steering_status"/>
67
<arg name="input_actuation_status" default="/vehicle/status/actuation_status"/>
78
<arg name="output_actuation_cmd" default="/control/command/actuation_cmd"/>
@@ -13,6 +14,7 @@
1314
<param from="$(var config_file)" allow_substs="true"/>
1415
<remap from="~/input/control_cmd" to="$(var input_control_cmd)"/>
1516
<remap from="~/input/odometry" to="$(var input_odometry)"/>
17+
<remap from="~/input/accel" to="$(var input_accel)"/>
1618
<remap from="~/input/steering" to="$(var input_steering)"/>
1719
<remap from="~/input/actuation_status" to="$(var input_actuation_status)"/>
1820
<remap from="~/output/actuation_cmd" to="$(var output_actuation_cmd)"/>

vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp

+29-19
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
3939
// for steering steer controller
4040
use_steer_ff_ = declare_parameter<bool>("use_steer_ff");
4141
use_steer_fb_ = declare_parameter<bool>("use_steer_fb");
42+
use_vehicle_adaptor_ = declare_parameter<bool>("use_vehicle_adaptor", false);
43+
4244
if (convert_accel_cmd_) {
4345
if (!accel_map_.readAccelMapFromCSV(csv_path_accel_map, true)) {
4446
throw std::invalid_argument("Accel map is invalid.");
@@ -120,10 +122,11 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
120122

121123
void RawVehicleCommandConverterNode::publishActuationCmd()
122124
{
123-
if (!current_twist_ptr_ || !control_cmd_ptr_ || !current_steer_ptr_) {
125+
/* check if all necessary data is available */
126+
if (!current_odometry_ || !control_cmd_ptr_ || !current_steer_ptr_) {
124127
RCLCPP_WARN_EXPRESSION(
125128
get_logger(), is_debugging_, "some pointers are null: %s, %s, %s",
126-
!current_twist_ptr_ ? "twist" : "", !control_cmd_ptr_ ? "cmd" : "",
129+
!current_odometry_ ? "odometry" : "", !control_cmd_ptr_ ? "cmd" : "",
127130
!current_steer_ptr_ ? "steer" : "");
128131
return;
129132
}
@@ -135,14 +138,29 @@ void RawVehicleCommandConverterNode::publishActuationCmd()
135138
}
136139
}
137140

141+
const auto current_accel = sub_accel_.takeData();
142+
if (use_vehicle_adaptor_) {
143+
if (!current_accel) {
144+
RCLCPP_WARN_EXPRESSION(get_logger(), is_debugging_, "current accel is null");
145+
return;
146+
}
147+
}
148+
149+
/* compensate control command if vehicle adaptor is enabled */
150+
const Control control_cmd = use_vehicle_adaptor_ ? vehicle_adaptor_.compensate(
151+
*control_cmd_ptr_, *current_odometry_,
152+
*current_accel, *current_steer_ptr_)
153+
: *control_cmd_ptr_;
154+
155+
/* calculate actuation command */
138156
double desired_accel_cmd = 0.0;
139157
double desired_brake_cmd = 0.0;
140158
double desired_steer_cmd = 0.0;
141159
ActuationCommandStamped actuation_cmd;
142-
const double acc = control_cmd_ptr_->longitudinal.acceleration;
143-
const double vel = current_twist_ptr_->twist.linear.x;
144-
const double steer = control_cmd_ptr_->lateral.steering_tire_angle;
145-
const double steer_rate = control_cmd_ptr_->lateral.steering_tire_rotation_rate;
160+
const double acc = control_cmd.longitudinal.acceleration;
161+
const double vel = current_odometry_->twist.twist.linear.x;
162+
const double steer = control_cmd.lateral.steering_tire_angle;
163+
const double steer_rate = control_cmd.lateral.steering_tire_rotation_rate;
146164
bool accel_cmd_is_zero = true;
147165
if (convert_accel_cmd_) {
148166
desired_accel_cmd = calculateAccelMap(vel, acc, accel_cmd_is_zero);
@@ -172,7 +190,7 @@ void RawVehicleCommandConverterNode::publishActuationCmd()
172190
desired_steer_cmd = calculateSteerFromMap(vel, steer, steer_rate);
173191
}
174192
actuation_cmd.header.frame_id = "base_link";
175-
actuation_cmd.header.stamp = control_cmd_ptr_->stamp;
193+
actuation_cmd.header.stamp = control_cmd.stamp;
176194
actuation_cmd.actuation.accel_cmd = desired_accel_cmd;
177195
actuation_cmd.actuation.brake_cmd = desired_brake_cmd;
178196
actuation_cmd.actuation.steer_cmd = desired_steer_cmd;
@@ -251,12 +269,7 @@ double RawVehicleCommandConverterNode::calculateBrakeMap(
251269

252270
void RawVehicleCommandConverterNode::onControlCmd(const Control::ConstSharedPtr msg)
253271
{
254-
const auto odometry_msg = sub_odometry_.takeData();
255-
if (odometry_msg) {
256-
current_twist_ptr_ = std::make_unique<TwistStamped>();
257-
current_twist_ptr_->header = odometry_msg->header;
258-
current_twist_ptr_->twist = odometry_msg->twist.twist;
259-
}
272+
current_odometry_ = sub_odometry_.takeData();
260273
control_cmd_ptr_ = msg;
261274
publishActuationCmd();
262275
}
@@ -276,14 +289,11 @@ void RawVehicleCommandConverterNode::onActuationStatus(
276289
}
277290

278291
// calculate steering status from actuation status
279-
const auto odometry_msg = sub_odometry_.takeData();
280-
if (odometry_msg) {
292+
current_odometry_ = sub_odometry_.takeData();
293+
if (current_odometry_) {
281294
if (convert_steer_cmd_method_.value() == "vgr") {
282-
current_twist_ptr_ = std::make_unique<TwistStamped>();
283-
current_twist_ptr_->header = odometry_msg->header;
284-
current_twist_ptr_->twist = odometry_msg->twist.twist;
285295
current_steer_ptr_ = std::make_unique<double>(vgr_.calculateSteeringTireState(
286-
current_twist_ptr_->twist.linear.x, actuation_status_ptr_->status.steer_status));
296+
current_odometry_->twist.twist.linear.x, actuation_status_ptr_->status.steer_status));
287297
Steering steering_msg{};
288298
steering_msg.steering_tire_angle = *current_steer_ptr_;
289299
pub_steering_status_->publish(steering_msg);
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
// Copyright 2024 Tier IV, Inc. All rights reserved.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "autoware_raw_vehicle_cmd_converter/vehicle_adaptor/vehicle_adaptor.hpp"
16+
17+
#include <iostream>
18+
19+
namespace autoware::raw_vehicle_cmd_converter
20+
{
21+
Control VehicleAdaptor::compensate(
22+
const Control & input_control_cmd, [[maybe_unused]] const Odometry & odometry,
23+
[[maybe_unused]] const AccelWithCovarianceStamped & accel, [[maybe_unused]] const double steering)
24+
{
25+
// TODO(someone): implement the control command compensation
26+
Control output_control_cmd = input_control_cmd;
27+
std::cerr << "vehicle adaptor: compensate control command" << std::endl;
28+
return output_control_cmd;
29+
}
30+
} // namespace autoware::raw_vehicle_cmd_converter

0 commit comments

Comments
 (0)