86 pub_brake_ =
node.advertise<dbw_fca_msgs::BrakeCmd>(
"brake_cmd", 1);
95 pub_gear_ =
node.advertise<dbw_fca_msgs::GearCmd>(
"gear_cmd", 1);
125 dbw_fca_msgs::BrakeCmd
msg;
129 msg.pedal_cmd_type = dbw_fca_msgs::BrakeCmd::CMD_PERCENT;
136 dbw_fca_msgs::ThrottleCmd
msg;
140 msg.pedal_cmd_type = dbw_fca_msgs::ThrottleCmd::CMD_PERCENT;
147 dbw_fca_msgs::SteeringCmd
msg;
152 msg.cmd_type = dbw_fca_msgs::SteeringCmd::CMD_ANGLE;
154 float raw_steering_cmd;
158 raw_steering_cmd = 0.5 * dbw_fca_msgs::SteeringCmd::ANGLE_MAX *
data_.
steering_joy;
165 msg.steering_wheel_angle_velocity =
svel_;
166 msg.steering_wheel_angle_cmd = filtered_steering_cmd;
168 msg.cmd_type = dbw_fca_msgs::SteeringCmd::CMD_TORQUE;
177 dbw_fca_msgs::GearCmd
msg;
198 ROS_ERROR_THROTTLE(2.0,
"Detected Logitech Gamepad F310 in DirectInput (D) mode. Please select (X) with the switch on the back to select XInput mode.");
248 case dbw_fca_msgs::TurnSignal::NONE:
255 case dbw_fca_msgs::TurnSignal::LEFT:
262 case dbw_fca_msgs::TurnSignal::RIGHT:
304 const std_msgs::Empty empty;