UlcNode.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include "UlcNode.h"
37 
38 namespace dataspeed_ulc_can
39 {
40 
41 template <typename T>
42 static void getParamWithSaturation(ros::NodeHandle &nh, const std::string& key, T& value, T min, T max)
43 {
44  if (nh.getParam(key, value)) {
45  if (value < min) {
46  value = min;
47  nh.setParam(key, value);
48  } else if (value > max) {
49  value = max;
50  nh.setParam(key, value);
51  }
52  }
53 }
54 
55 template <class T>
56 static T overflowSaturation(double input, T limit_min, T limit_max, double scale_factor, const std::string& input_name, const std::string& units)
57 {
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());
60  return limit_min;
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());
63  return limit_max;
64  } else {
65  return input / scale_factor;
66  }
67 }
68 
69 static inline bool validInputs(const dataspeed_ulc_msgs::UlcCmd& cmd)
70 {
71  bool valid = true;
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");
74  valid = false;
75  }
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");
78  valid = false;
79  }
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");
82  valid = false;
83  }
84  if (std::isnan(cmd.yaw_command)) {
85  ROS_WARN("NaN input detected on yaw command input");
86  valid = false;
87  }
88  if (std::isnan(cmd.linear_accel)) {
89  ROS_WARN("NaN input detected on linear accel input");
90  valid = false;
91  }
92  if (std::isnan(cmd.linear_decel)) {
93  ROS_WARN("NaN input detected on linear decel input");
94  valid = false;
95  }
96  if (std::isnan(cmd.lateral_accel)) {
97  ROS_WARN("NaN input detected on lateral accel input");
98  valid = false;
99  }
100  if (std::isnan(cmd.angular_accel)) {
101  ROS_WARN("NaN input detected on angular accel input");
102  valid = false;
103  }
104  if (std::isnan(cmd.jerk_limit_throttle)) {
105  ROS_WARN("NaN input detected on throttle jerk input");
106  valid = false;
107  }
108  if (std::isnan(cmd.jerk_limit_brake)) {
109  ROS_WARN("NaN input detected on brake jerk input");
110  valid = false;
111  }
112  return valid;
113 }
114 
115 // Last firmware versions before new ULC interface
128 });
129 
131  enable_(false), accel_mode_supported_(true)
132 {
133  // Setup publishers
134  pub_report_ = n.advertise<dataspeed_ulc_msgs::UlcReport>("ulc_report", 2);
135  pub_can_ = n.advertise<can_msgs::Frame>("can_tx", 100);
136 
137  // Setup subscribers
139  sub_can_ = n.subscribe<can_msgs::Frame>("can_rx", 100, &UlcNode::recvCan, this, NODELAY);
140  sub_cmd_ = n.subscribe<dataspeed_ulc_msgs::UlcCmd>("ulc_cmd", 2, &UlcNode::recvUlcCmd, this, NODELAY);
141  sub_twist_ = n.subscribe<geometry_msgs::Twist>("cmd_vel", 2, &UlcNode::recvTwist, this, NODELAY);
142  sub_twist_stamped_ = n.subscribe<geometry_msgs::TwistStamped>("cmd_vel_stamped", 2, &UlcNode::recvTwistStamped, this, NODELAY);
143  sub_enable_ = n.subscribe<std_msgs::Bool>("dbw_enabled", 2, &UlcNode::recvEnable, this, NODELAY);
144 
145  // Setup timer for config message retransmission
146  double freq = 5.0;
147  getParamWithSaturation(pn, "config_frequency", freq, 5.0, 50.0);
149 }
150 
151 void UlcNode::recvEnable(const std_msgs::BoolConstPtr& msg)
152 {
153  enable_ = msg->data;
154 }
155 
156 void UlcNode::recvUlcCmd(const dataspeed_ulc_msgs::UlcCmdConstPtr& msg)
157 {
158  // Check for differences in acceleration and jerk limits
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);
165  ulc_cmd_ = *msg;
166 
167  // Publish command message
168  sendCmdMsg(true);
169 
170  // Publish config message on change
171  if (diff) {
172  sendCfgMsg();
173  }
174 }
175 
176 void UlcNode::recvTwistCmd(const geometry_msgs::Twist& msg)
177 {
178  // Populate command fields
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;
184 
185  // Set other fields to default values
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;
197 
198  // Publish command message
199  sendCmdMsg(false);
200 }
201 
202 void UlcNode::recvTwist(const geometry_msgs::TwistConstPtr& msg)
203 {
204  recvTwistCmd(*msg);
205 }
206 
207 void UlcNode::recvTwistStamped(const geometry_msgs::TwistStampedConstPtr& msg)
208 {
209  recvTwistCmd(msg->twist);
210 }
211 
212 void UlcNode::recvCan(const can_msgs::FrameConstPtr& msg)
213 {
214  if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
215  switch (msg->id) {
216  case ID_ULC_REPORT:
217  if (msg->dlc >= sizeof(MsgUlcReport)) {
218  const MsgUlcReport *ptr = (const MsgUlcReport *)msg->data.elems;
219  dataspeed_ulc_msgs::UlcReport report;
220  report.header.stamp = msg->header.stamp;
221  report.speed_ref = (float)ptr->speed_ref * 0.02f;
222  report.timeout = ptr->timeout;
223  report.pedals_enabled = ptr->pedals_enabled;
224  report.pedals_mode = ptr->pedals_mode;
225  report.speed_meas = (float)ptr->speed_meas * 0.02f;
226  report.override_latched = ptr->override;
227  report.steering_enabled = ptr->steering_enabled;
228  report.steering_mode = ptr->steering_mode;
229  report.accel_ref = (float)ptr->accel_ref * 0.05f;
230  report.accel_meas = (float)ptr->accel_meas * 0.05f;
231  report.max_steering_angle = (float)ptr->max_steering_angle * 5.0f;
232  report.coasting = ptr->coasting;
233  report.max_steering_vel = (float)ptr->max_steering_vel * 8.0f;
234  report.steering_preempted = ptr->steering_preempted;
235  report.speed_preempted = ptr->speed_preempted;
236  pub_report_.publish(report);
237  }
238  break;
239  case ID_VERSION:
240  if (msg->dlc >= sizeof(MsgVersion)) {
241  const MsgVersion *ptr = (const MsgVersion*)msg->data.elems;
242  if ((Module)ptr->module == M_STEER) {
243  const PlatformVersion version((Platform)ptr->platform, (Module)ptr->module, ptr->major, ptr->minor, ptr->build);
244  const ModuleVersion old_ulc_version = OLD_ULC_FIRMWARE.findModule(version);
245  const char * str_p = platformToString(version.p);
246  const char * str_m = moduleToString(version.m);
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,
252  version.v.major(), version.v.minor(), version.v.build());
253  }
254  }
255  }
256  }
257  break;
258  }
259  }
260 }
261 
262 void UlcNode::sendCmdMsg(bool cfg)
263 {
264  // Validate input fields
265  if (validInputs(ulc_cmd_)) {
266  if (cfg) {
268  }
269  } else {
270  cmd_stamp_ = ros::Time(0);
271  return;
272  }
273 
274  // Build CAN message
275  can_msgs::Frame msg;
276  msg.id = ID_ULC_CMD;
277  msg.is_extended = false;
278  msg.dlc = sizeof(MsgUlcCmd);
279  MsgUlcCmd *ptr = (MsgUlcCmd *)msg.data.elems;
280  memset(ptr, 0x00, sizeof(*ptr));
281 
282  // Populate enable bits
283  if (enable_) {
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;
288  }
289 
290  // Populate command fields
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) {
296  ptr->lon_command =
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_) {
300  ROS_WARN_THROTTLE(1.0, "Firmware does not support acceleration mode interface");
301  return;
302  }
303  ptr->lon_command =
304  overflowSaturation(ulc_cmd_.accel_cmd, INT16_MIN, INT16_MAX, 5e-4, "ULC command accel", "m/s^2");
305  } else {
306  ptr->lon_command = 0;
307  ROS_WARN_THROTTLE(1.0, "Unsupported ULC pedal control mode [%d]", ulc_cmd_.pedals_mode);
308  cmd_stamp_ = ros::Time(0);
309  return;
310  }
311 
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");
316  } else {
317  ptr->yaw_command = 0;
318  ROS_WARN_THROTTLE(1.0, "Unsupported ULC steering control mode [%d]", ulc_cmd_.steering_mode);
319  cmd_stamp_ = ros::Time(0);
320  return;
321  }
322 
323  // Publish message
324  pub_can_.publish(msg);
325 }
326 
328 {
329  // Build CAN message
330  can_msgs::Frame msg;
331  msg.id = ID_ULC_CONFIG;
332  msg.is_extended = false;
333  msg.dlc = sizeof(MsgUlcCfg);
334  MsgUlcCfg *ptr = (MsgUlcCfg *)msg.data.elems;
335  memset(ptr, 0x00, sizeof(*ptr));
336 
337  // Populate acceleration and jerk limits
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");
344 
345  // Publish message
346  pub_can_.publish(msg);
347 
348  // Reset timer
351 }
352 
354 {
355  // Retransmit config message while command is valid
356  if (event.current_real - cmd_stamp_ < ros::Duration(0.1)) {
357  sendCfgMsg();
358  }
359 }
360 
361 }
ModuleVersion findModule(Module m) const
Definition: PlatformMap.h:65
ros::Subscriber sub_twist_stamped_
Definition: UlcNode.h:68
void recvEnable(const std_msgs::BoolConstPtr &msg)
Definition: UlcNode.cpp:151
void recvTwistCmd(const geometry_msgs::Twist &msg)
Definition: UlcNode.cpp:176
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static const char * platformToString(Platform x)
void sendCmdMsg(bool cfg)
Definition: UlcNode.cpp:262
void recvCan(const can_msgs::FrameConstPtr &msg)
Definition: UlcNode.cpp:212
ros::NodeHandle * n
void stop()
ros::NodeHandle * pn
void start()
void insert(Platform p, Module m, ModuleVersion v)
Definition: PlatformMap.h:59
#define ROS_WARN(...)
ros::Subscriber sub_cmd_
Definition: UlcNode.h:66
dataspeed_ulc_msgs::UlcCmd ulc_cmd_
Definition: UlcNode.h:75
TransportHints & tcpNoDelay(bool nodelay=true)
void publish(const boost::shared_ptr< M > &message) const
void recvTwist(const geometry_msgs::TwistConstPtr &msg)
Definition: UlcNode.cpp:202
UlcNode(ros::NodeHandle &n, ros::NodeHandle &pn)
Definition: UlcNode.cpp:130
#define ROS_WARN_THROTTLE(period,...)
bool getParam(const std::string &key, std::string &s) const
ros::Timer config_timer_
Definition: UlcNode.h:73
PlatformMap OLD_ULC_FIRMWARE({ {PlatformVersion(P_FCA_RU, M_STEER, ModuleVersion(1, 5, 2))}, {PlatformVersion(P_FCA_WK2, M_STEER, ModuleVersion(1, 3, 2))}, {PlatformVersion(P_FORD_C1, M_STEER, ModuleVersion(1, 2, 2))}, {PlatformVersion(P_FORD_CD4, M_STEER, ModuleVersion(2, 5, 2))}, {PlatformVersion(P_FORD_CD5, M_STEER, ModuleVersion(1, 1, 2))}, {PlatformVersion(P_FORD_GE1, M_STEER, ModuleVersion(0, 1, 0))}, {PlatformVersion(P_FORD_P5, M_STEER, ModuleVersion(1, 4, 2))}, {PlatformVersion(P_FORD_T6, M_STEER, ModuleVersion(0, 2, 2))}, {PlatformVersion(P_FORD_U6, M_STEER, ModuleVersion(1, 0, 2))}, {PlatformVersion(P_POLARIS_GEM, M_STEER, ModuleVersion(1, 1, 1))}, {PlatformVersion(P_POLARIS_RZR, M_STEER, ModuleVersion(0, 3, 1))}, })
void recvTwistStamped(const geometry_msgs::TwistStampedConstPtr &msg)
Definition: UlcNode.cpp:207
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Subscriber sub_can_
Definition: UlcNode.h:69
ros::Subscriber sub_enable_
Definition: UlcNode.h:70
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ros::Publisher pub_can_
Definition: UlcNode.h:72
PlatformMap firmware_
Definition: UlcNode.h:81
ros::Publisher pub_report_
Definition: UlcNode.h:71
static T overflowSaturation(double input, T limit_min, T limit_max, double scale_factor, const std::string &input_name, const std::string &units)
Definition: UlcNode.cpp:56
static Time now()
ros::Subscriber sub_twist_
Definition: UlcNode.h:67
static void getParamWithSaturation(ros::NodeHandle &nh, const std::string &key, T &value, T min, T max)
Definition: UlcNode.cpp:42
void recvUlcCmd(const dataspeed_ulc_msgs::UlcCmdConstPtr &msg)
Definition: UlcNode.cpp:156
static bool validInputs(const dataspeed_ulc_msgs::UlcCmd &cmd)
Definition: UlcNode.cpp:69
static const char * moduleToString(Module x)
void configTimerCb(const ros::TimerEvent &event)
Definition: UlcNode.cpp:353


dataspeed_ulc_can
Author(s): Micho Radovnikovich
autogenerated on Fri Dec 2 2022 03:20:37