48 }
else if (value > max) {
56 static T
overflowSaturation(
double input, T limit_min, T limit_max,
double scale_factor,
const std::string& input_name,
const std::string& units)
58 if (input < (limit_min * scale_factor)) {
59 ROS_WARN(
"%s [%f %s] out of range -- saturating to %f %s", input_name.c_str(), input, units.c_str(), limit_min * scale_factor, units.c_str());
61 }
else if (input > (limit_max * scale_factor)) {
62 ROS_WARN(
"%s [%f %s] out of range -- saturating to %f %s", input_name.c_str(), input, units.c_str(), limit_max * scale_factor, units.c_str());
65 return input / scale_factor;
69 static inline bool validInputs(
const dataspeed_ulc_msgs::UlcCmd& cmd)
72 if (std::isnan(
cmd.linear_velocity) &&
cmd.pedals_mode == dataspeed_ulc_msgs::UlcCmd::SPEED_MODE) {
73 ROS_WARN(
"NaN input detected on speed input");
76 if (std::isnan(
cmd.accel_cmd) &&
cmd.pedals_mode == dataspeed_ulc_msgs::UlcCmd::ACCEL_MODE) {
77 ROS_WARN(
"NaN input detected on speed input");
80 if (
cmd.pedals_mode != dataspeed_ulc_msgs::UlcCmd::SPEED_MODE &&
cmd.pedals_mode != dataspeed_ulc_msgs::UlcCmd::ACCEL_MODE) {
81 ROS_WARN(
"Invalid pedals mode in command message");
84 if (std::isnan(
cmd.yaw_command)) {
85 ROS_WARN(
"NaN input detected on yaw command input");
88 if (std::isnan(
cmd.linear_accel)) {
89 ROS_WARN(
"NaN input detected on linear accel input");
92 if (std::isnan(
cmd.linear_decel)) {
93 ROS_WARN(
"NaN input detected on linear decel input");
96 if (std::isnan(
cmd.lateral_accel)) {
97 ROS_WARN(
"NaN input detected on lateral accel input");
100 if (std::isnan(
cmd.angular_accel)) {
101 ROS_WARN(
"NaN input detected on angular accel input");
104 if (std::isnan(
cmd.jerk_limit_throttle)) {
105 ROS_WARN(
"NaN input detected on throttle jerk input");
108 if (std::isnan(
cmd.jerk_limit_brake)) {
109 ROS_WARN(
"NaN input detected on brake jerk input");
131 enable_(false), accel_mode_supported_(true)
134 pub_report_ =
n.
advertise<dataspeed_ulc_msgs::UlcReport>(
"ulc_report", 2);
135 pub_can_ =
n.
advertise<can_msgs::Frame>(
"can_tx", 100);
151 void UlcNode::recvEnable(
const std_msgs::BoolConstPtr& msg)
156 void UlcNode::recvUlcCmd(
const dataspeed_ulc_msgs::UlcCmdConstPtr& msg)
159 bool diff = (msg->linear_accel != ulc_cmd_.linear_accel)
160 || (msg->linear_decel != ulc_cmd_.linear_decel)
161 || (msg->lateral_accel != ulc_cmd_.lateral_accel)
162 || (msg->angular_accel != ulc_cmd_.angular_accel)
163 || (msg->jerk_limit_throttle != ulc_cmd_.jerk_limit_throttle)
164 || (msg->jerk_limit_brake != ulc_cmd_.jerk_limit_brake);
176 void UlcNode::recvTwistCmd(
const geometry_msgs::Twist& msg)
179 ulc_cmd_.linear_velocity = msg.linear.x;
180 ulc_cmd_.pedals_mode = dataspeed_ulc_msgs::UlcCmd::SPEED_MODE;
181 ulc_cmd_.coast_decel =
false;
182 ulc_cmd_.yaw_command = msg.angular.z;
183 ulc_cmd_.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
186 ulc_cmd_.clear =
false;
187 ulc_cmd_.enable_pedals =
true;
188 ulc_cmd_.enable_shifting =
true;
189 ulc_cmd_.enable_steering =
true;
190 ulc_cmd_.shift_from_park =
false;
191 ulc_cmd_.linear_accel = 0;
192 ulc_cmd_.linear_decel = 0;
193 ulc_cmd_.angular_accel = 0;
194 ulc_cmd_.lateral_accel = 0;
195 ulc_cmd_.jerk_limit_throttle = 0;
196 ulc_cmd_.jerk_limit_brake = 0;
202 void UlcNode::recvTwist(
const geometry_msgs::TwistConstPtr& msg)
207 void UlcNode::recvTwistStamped(
const geometry_msgs::TwistStampedConstPtr& msg)
209 recvTwistCmd(msg->twist);
214 if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
219 dataspeed_ulc_msgs::UlcReport report;
220 report.header.stamp = msg->header.stamp;
225 report.speed_meas = (float)ptr->
speed_meas * 0.02f;
226 report.override_latched = ptr->
override;
229 report.accel_ref = (
float)ptr->
accel_ref * 0.05f;
230 report.accel_meas = (float)ptr->
accel_meas * 0.05f;
236 pub_report_.publish(report);
247 if (firmware_.findModule(version) != version.
v) {
248 firmware_.insert(version);
249 if (version <= old_ulc_version) {
250 accel_mode_supported_ =
false;
251 ROS_WARN(
"Firmware %s %s version %u.%u.%u does not support ULC acceleration interface mode.", str_p, str_m,
262 void UlcNode::sendCmdMsg(
bool cfg)
277 msg.is_extended =
false;
278 msg.dlc =
sizeof(MsgUlcCmd);
279 MsgUlcCmd *ptr = (MsgUlcCmd *)msg.data.elems;
280 memset(ptr, 0x00,
sizeof(*ptr));
284 ptr->enable_pedals = ulc_cmd_.enable_pedals;
285 ptr->enable_steering = ulc_cmd_.enable_steering;
286 ptr->enable_shifting = ulc_cmd_.enable_shifting;
287 ptr->shift_from_park = ulc_cmd_.shift_from_park;
291 ptr->clear = ulc_cmd_.clear;
292 ptr->pedals_mode = ulc_cmd_.pedals_mode;
293 ptr->coast_decel = ulc_cmd_.coast_decel;
294 ptr->steering_mode = ulc_cmd_.steering_mode;
295 if (ulc_cmd_.pedals_mode == dataspeed_ulc_msgs::UlcCmd::SPEED_MODE) {
297 overflowSaturation(ulc_cmd_.linear_velocity, INT16_MIN, INT16_MAX, 0.0025,
"ULC command speed",
"m/s");
298 }
else if (ulc_cmd_.pedals_mode == dataspeed_ulc_msgs::UlcCmd::ACCEL_MODE) {
299 if (!accel_mode_supported_) {
304 overflowSaturation(ulc_cmd_.accel_cmd, INT16_MIN, INT16_MAX, 5e-4,
"ULC command accel",
"m/s^2");
306 ptr->lon_command = 0;
307 ROS_WARN_THROTTLE(1.0,
"Unsupported ULC pedal control mode [%d]", ulc_cmd_.pedals_mode);
312 if (ulc_cmd_.steering_mode == dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE) {
313 ptr->yaw_command =
overflowSaturation(ulc_cmd_.yaw_command, INT16_MIN, INT16_MAX, 0.00025,
"ULC yaw rate command",
"rad/s");
314 }
else if (ulc_cmd_.steering_mode == dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE) {
315 ptr->yaw_command =
overflowSaturation(ulc_cmd_.yaw_command, INT16_MIN, INT16_MAX, 0.0000061,
"ULC curvature command",
"1/m");
317 ptr->yaw_command = 0;
318 ROS_WARN_THROTTLE(1.0,
"Unsupported ULC steering control mode [%d]", ulc_cmd_.steering_mode);
324 pub_can_.publish(msg);
327 void UlcNode::sendCfgMsg()
332 msg.is_extended =
false;
333 msg.dlc =
sizeof(MsgUlcCfg);
334 MsgUlcCfg *ptr = (MsgUlcCfg *)msg.data.elems;
335 memset(ptr, 0x00,
sizeof(*ptr));
338 ptr->linear_accel =
overflowSaturation(ulc_cmd_.linear_accel, 0, UINT8_MAX, 0.025,
"Linear accel limit",
"m/s^2");
339 ptr->linear_decel =
overflowSaturation(ulc_cmd_.linear_decel, 0, UINT8_MAX, 0.025,
"Linear decel limit",
"m/s^2");
340 ptr->lateral_accel =
overflowSaturation(ulc_cmd_.lateral_accel, 0, UINT8_MAX, 0.05,
"Lateral accel limit",
"m/s^2");
341 ptr->angular_accel =
overflowSaturation(ulc_cmd_.angular_accel, 0, UINT8_MAX, 0.02,
"Angular accel limit",
"rad/s^2");
342 ptr->jerk_limit_throttle =
overflowSaturation(ulc_cmd_.jerk_limit_throttle, 0, UINT8_MAX, 0.1,
"Throttle jerk limit",
"m/s^3");
343 ptr->jerk_limit_brake =
overflowSaturation(ulc_cmd_.jerk_limit_brake, 0, UINT8_MAX, 0.1,
"Brake jerk limit",
"m/s^3");
346 pub_can_.publish(msg);
349 config_timer_.stop();
350 config_timer_.start();