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)
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);
179 ulc_cmd_.linear_velocity = msg.linear.x;
180 ulc_cmd_.pedals_mode = dataspeed_ulc_msgs::UlcCmd::SPEED_MODE;
182 ulc_cmd_.yaw_command = msg.angular.z;
183 ulc_cmd_.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
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;
249 if (version <= old_ulc_version) {
251 ROS_WARN(
"Firmware %s %s version %u.%u.%u does not support ULC acceleration interface mode.", str_p, str_m,
277 msg.is_extended =
false;
280 memset(ptr, 0x00,
sizeof(*ptr));
295 if (
ulc_cmd_.pedals_mode == dataspeed_ulc_msgs::UlcCmd::SPEED_MODE) {
298 }
else if (
ulc_cmd_.pedals_mode == dataspeed_ulc_msgs::UlcCmd::ACCEL_MODE) {
312 if (
ulc_cmd_.steering_mode == dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE) {
314 }
else if (
ulc_cmd_.steering_mode == dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE) {
332 msg.is_extended =
false;
335 memset(ptr, 0x00,
sizeof(*ptr));
ros::Subscriber sub_twist_stamped_
void recvEnable(const std_msgs::BoolConstPtr &msg)
uint8_t jerk_limit_throttle
void recvTwistCmd(const geometry_msgs::Twist &msg)
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)
void recvCan(const can_msgs::FrameConstPtr &msg)
dataspeed_ulc_msgs::UlcCmd ulc_cmd_
uint16_t steering_enabled
TransportHints & tcpNoDelay(bool nodelay=true)
void publish(const boost::shared_ptr< M > &message) const
void recvTwist(const geometry_msgs::TwistConstPtr &msg)
UlcNode(ros::NodeHandle &n, ros::NodeHandle &pn)
#define ROS_WARN_THROTTLE(period,...)
bool getParam(const std::string &key, std::string &s) const
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)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint8_t steering_preempted
ros::Subscriber sub_enable_
uint8_t max_steering_angle
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ros::Publisher pub_report_
static T overflowSaturation(double input, T limit_min, T limit_max, double scale_factor, const std::string &input_name, const std::string &units)
ros::Subscriber sub_twist_
static void getParamWithSaturation(ros::NodeHandle &nh, const std::string &key, T &value, T min, T max)
void recvUlcCmd(const dataspeed_ulc_msgs::UlcCmdConstPtr &msg)
bool accel_mode_supported_
static bool validInputs(const dataspeed_ulc_msgs::UlcCmd &cmd)
static const char * moduleToString(Module x)
void configTimerCb(const ros::TimerEvent &event)