@@ -39,6 +39,8 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
39
39
// for steering steer controller
40
40
use_steer_ff_ = declare_parameter<bool >(" use_steer_ff" );
41
41
use_steer_fb_ = declare_parameter<bool >(" use_steer_fb" );
42
+ use_vehicle_adaptor_ = declare_parameter<bool >(" use_vehicle_adaptor" , false );
43
+
42
44
if (convert_accel_cmd_) {
43
45
if (!accel_map_.readAccelMapFromCSV (csv_path_accel_map, true )) {
44
46
throw std::invalid_argument (" Accel map is invalid." );
@@ -120,10 +122,11 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
120
122
121
123
void RawVehicleCommandConverterNode::publishActuationCmd ()
122
124
{
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_) {
124
127
RCLCPP_WARN_EXPRESSION (
125
128
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" : " " ,
127
130
!current_steer_ptr_ ? " steer" : " " );
128
131
return ;
129
132
}
@@ -135,14 +138,29 @@ void RawVehicleCommandConverterNode::publishActuationCmd()
135
138
}
136
139
}
137
140
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 */
138
156
double desired_accel_cmd = 0.0 ;
139
157
double desired_brake_cmd = 0.0 ;
140
158
double desired_steer_cmd = 0.0 ;
141
159
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 ;
146
164
bool accel_cmd_is_zero = true ;
147
165
if (convert_accel_cmd_) {
148
166
desired_accel_cmd = calculateAccelMap (vel, acc, accel_cmd_is_zero);
@@ -172,7 +190,7 @@ void RawVehicleCommandConverterNode::publishActuationCmd()
172
190
desired_steer_cmd = calculateSteerFromMap (vel, steer, steer_rate);
173
191
}
174
192
actuation_cmd.header .frame_id = " base_link" ;
175
- actuation_cmd.header .stamp = control_cmd_ptr_-> stamp ;
193
+ actuation_cmd.header .stamp = control_cmd. stamp ;
176
194
actuation_cmd.actuation .accel_cmd = desired_accel_cmd;
177
195
actuation_cmd.actuation .brake_cmd = desired_brake_cmd;
178
196
actuation_cmd.actuation .steer_cmd = desired_steer_cmd;
@@ -251,12 +269,7 @@ double RawVehicleCommandConverterNode::calculateBrakeMap(
251
269
252
270
void RawVehicleCommandConverterNode::onControlCmd (const Control::ConstSharedPtr msg)
253
271
{
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 ();
260
273
control_cmd_ptr_ = msg;
261
274
publishActuationCmd ();
262
275
}
@@ -276,14 +289,11 @@ void RawVehicleCommandConverterNode::onActuationStatus(
276
289
}
277
290
278
291
// 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_ ) {
281
294
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 ;
285
295
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 ));
287
297
Steering steering_msg{};
288
298
steering_msg.steering_tire_angle = *current_steer_ptr_;
289
299
pub_steering_status_->publish (steering_msg);
0 commit comments