UlcNode.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include "UlcNode.h"
00036 #include <dataspeed_ulc_can/dispatch.h>
00037 
00038 namespace dataspeed_ulc_can
00039 {
00040 
00041 template <typename T>
00042 static void getParamWithSaturation(ros::NodeHandle &nh, const std::string& key, T& value, T min, T max)
00043 {
00044   if (nh.getParam(key, value)) {
00045     if (value < min) {
00046       value = min;
00047       nh.setParam(key, value);
00048     } else if (value > max) {
00049       value = max;
00050       nh.setParam(key, value);
00051     }
00052   }
00053 }
00054 
00055 template <class T>
00056 static T overflowSaturation(double input, T limit_min, T limit_max, double scale_factor, const std::string& input_name, const std::string& units)
00057 {
00058   if (input < (limit_min * scale_factor)) {
00059     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());
00060     return limit_min;
00061   } else if (input > (limit_max * scale_factor)) {
00062     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());
00063     return limit_max;
00064   } else {
00065     return input / scale_factor;
00066   }
00067 }
00068 
00069 static inline bool validInputs(const dataspeed_ulc_msgs::UlcCmd& cmd)
00070 {
00071   bool valid = true;
00072   if (std::isnan(cmd.linear_velocity)) {
00073     ROS_WARN("NaN input detected on speed input");
00074     valid = false;
00075   }
00076   if (std::isnan(cmd.yaw_command)) {
00077     ROS_WARN("NaN input detected on yaw command input");
00078     valid = false;
00079   }
00080   if (std::isnan(cmd.linear_accel)) {
00081     ROS_WARN("NaN input detected on linear accel input");
00082     valid = false;
00083   }
00084   if (std::isnan(cmd.linear_decel)) {
00085     ROS_WARN("NaN input detected on linear decel input");
00086     valid = false;
00087   }
00088   if (std::isnan(cmd.lateral_accel)) {
00089     ROS_WARN("NaN input detected on lateral accel input");
00090     valid = false;
00091   }
00092   if (std::isnan(cmd.angular_accel)) {
00093     ROS_WARN("NaN input detected on angular accel input");
00094     valid = false;
00095   }
00096   return valid;
00097 }
00098 
00099 UlcNode::UlcNode(ros::NodeHandle &n, ros::NodeHandle &pn) :
00100   enable_(false)
00101 {
00102   // Setup publishers
00103   pub_report_ = n.advertise<dataspeed_ulc_msgs::UlcReport>("ulc_report", 2);
00104   pub_can_ = n.advertise<can_msgs::Frame>("can_tx", 100);
00105 
00106   // Setup subscribers
00107   const ros::TransportHints NODELAY = ros::TransportHints().tcpNoDelay();
00108   sub_can_ = n.subscribe<can_msgs::Frame>("can_rx", 100, &UlcNode::recvCan, this, NODELAY);
00109   sub_cmd_ = n.subscribe<dataspeed_ulc_msgs::UlcCmd>("ulc_cmd", 2, &UlcNode::recvUlcCmd, this, NODELAY);
00110   sub_twist_ = n.subscribe<geometry_msgs::Twist>("cmd_vel", 2, &UlcNode::recvTwist, this, NODELAY);
00111   sub_twist_stamped_ = n.subscribe<geometry_msgs::TwistStamped>("cmd_vel_stamped", 2, &UlcNode::recvTwistStamped, this, NODELAY);
00112   sub_enable_ = n.subscribe<std_msgs::Bool>("dbw_enabled", 2, &UlcNode::recvEnable, this, NODELAY);
00113 
00114   // Setup timer for config message retransmission
00115   double freq = 5.0;
00116   getParamWithSaturation(pn, "config_frequency", freq, 5.0, 50.0);
00117   config_timer_ = n.createTimer(ros::Duration(1.0 / freq), &UlcNode::configTimerCb, this);
00118 }
00119 
00120 void UlcNode::recvEnable(const std_msgs::BoolConstPtr& msg)
00121 {
00122   enable_ = msg->data;
00123 }
00124 
00125 void UlcNode::recvUlcCmd(const dataspeed_ulc_msgs::UlcCmdConstPtr& msg)
00126 {
00127   // Check for differences in acceleration limits
00128   bool diff = (msg->linear_accel  != ulc_cmd_.linear_accel)
00129            || (msg->linear_decel  != ulc_cmd_.linear_decel)
00130            || (msg->lateral_accel != ulc_cmd_.lateral_accel)
00131            || (msg->angular_accel != ulc_cmd_.angular_accel);
00132   ulc_cmd_ = *msg;
00133 
00134   // Publish command message
00135   sendCmdMsg(true);
00136 
00137   // Publish config message on change
00138   if (diff) {
00139     sendCfgMsg();
00140   }
00141 }
00142 
00143 void UlcNode::recvTwistCmd(const geometry_msgs::Twist& msg)
00144 {
00145   // Populate command fields
00146   ulc_cmd_.linear_velocity = msg.linear.x;
00147   ulc_cmd_.yaw_command = msg.angular.z;
00148   ulc_cmd_.steering_mode = dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE;
00149 
00150   // Set other fields to default values
00151   ulc_cmd_.clear = false;
00152   ulc_cmd_.enable_pedals = true;
00153   ulc_cmd_.enable_shifting = true;
00154   ulc_cmd_.enable_steering = true;
00155   ulc_cmd_.shift_from_park = false;
00156   ulc_cmd_.linear_accel = 0;
00157   ulc_cmd_.linear_decel = 0;
00158   ulc_cmd_.angular_accel = 0;
00159   ulc_cmd_.lateral_accel = 0;
00160 
00161   // Publish command message
00162   sendCmdMsg(false);
00163 }
00164 
00165 void UlcNode::recvTwist(const geometry_msgs::TwistConstPtr& msg)
00166 {
00167   recvTwistCmd(*msg);
00168 }
00169 
00170 void UlcNode::recvTwistStamped(const geometry_msgs::TwistStampedConstPtr& msg)
00171 {
00172   recvTwistCmd(msg->twist);
00173 }
00174 
00175 void UlcNode::recvCan(const can_msgs::FrameConstPtr& msg)
00176 {
00177   if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
00178     switch (msg->id) {
00179       case ID_ULC_REPORT:
00180         if (msg->dlc >= sizeof(MsgUlcReport)) {
00181           const MsgUlcReport *ptr = (const MsgUlcReport *)msg->data.elems;
00182           dataspeed_ulc_msgs::UlcReport report;
00183           report.header.stamp = msg->header.stamp;
00184           report.speed_ref = (float)ptr->speed_ref * 0.02f;
00185           report.accel_ref = (float)ptr->accel_ref * 0.05f;
00186           report.speed_meas = (float)ptr->speed_meas * 0.02f;
00187           report.accel_meas = (float)ptr->accel_meas * 0.05f;
00188           report.max_steering_angle = (float)ptr->max_steering_angle * 5.0f;
00189           report.max_steering_vel = (float)ptr->max_steering_vel * 8.0f;
00190           report.pedals_enabled = ptr->pedals_enabled;
00191           report.steering_enabled = ptr->steering_enabled;
00192           report.tracking_mode = ptr->tracking_mode;
00193           report.speed_preempted = ptr->speed_preempted;
00194           report.steering_preempted = ptr->steering_preempted;
00195           report.override_latched = ptr->override;
00196           report.steering_mode = ptr->steering_mode;
00197           report.timeout = ptr->timeout;
00198           pub_report_.publish(report);
00199         }
00200         break;
00201     }
00202   }
00203 }
00204 
00205 void UlcNode::sendCmdMsg(bool cfg)
00206 {
00207   // Validate input fields
00208   if (validInputs(ulc_cmd_)) {
00209     if (cfg) {
00210       cmd_stamp_ = ros::Time::now();
00211     }
00212   } else {
00213     cmd_stamp_ = ros::Time(0);
00214     return;
00215   }
00216 
00217   // Build CAN message
00218   can_msgs::Frame msg;
00219   msg.id = ID_ULC_CMD;
00220   msg.is_extended = false;
00221   msg.dlc = sizeof(MsgUlcCmd);
00222   MsgUlcCmd *ptr = (MsgUlcCmd *)msg.data.elems;
00223   memset(ptr, 0x00, sizeof(*ptr));
00224 
00225   // Populate enable bits
00226   if (enable_) {
00227     ptr->enable_pedals = ulc_cmd_.enable_pedals;
00228     ptr->enable_steering = ulc_cmd_.enable_steering;
00229     ptr->enable_shifting = ulc_cmd_.enable_shifting;
00230     ptr->shift_from_park = ulc_cmd_.shift_from_park;
00231   }
00232 
00233   // Populate command fields
00234   ptr->clear = ulc_cmd_.clear;
00235   ptr->linear_velocity = overflowSaturation(ulc_cmd_.linear_velocity, INT16_MIN, INT16_MAX, 0.0025, "ULC command speed", "m/s");
00236   ptr->steering_mode = ulc_cmd_.steering_mode;
00237   if (ulc_cmd_.steering_mode == dataspeed_ulc_msgs::UlcCmd::YAW_RATE_MODE) {
00238     ptr->yaw_command = overflowSaturation(ulc_cmd_.yaw_command, INT16_MIN, INT16_MAX, 0.00025, "ULC yaw rate command", "rad/s");
00239   } else if (ulc_cmd_.steering_mode == dataspeed_ulc_msgs::UlcCmd::CURVATURE_MODE) {
00240     ptr->yaw_command = overflowSaturation(ulc_cmd_.yaw_command, INT16_MIN, INT16_MAX, 0.0000061, "ULC curvature command", "1/m");
00241   } else {
00242     ptr->yaw_command = 0;
00243     ROS_WARN_THROTTLE(1.0, "Unsupported ULC steering control mode [%d]", ulc_cmd_.steering_mode);
00244     cmd_stamp_ = ros::Time(0);
00245     return;
00246   }
00247 
00248   // Publish message
00249   pub_can_.publish(msg);
00250 }
00251 
00252 void UlcNode::sendCfgMsg()
00253 {
00254   // Build CAN message
00255   can_msgs::Frame msg;
00256   msg.id = ID_ULC_CONFIG;
00257   msg.is_extended = false;
00258   msg.dlc = sizeof(MsgUlcCfg);
00259   MsgUlcCfg *ptr = (MsgUlcCfg *)msg.data.elems;
00260   memset(ptr, 0x00, sizeof(*ptr));
00261 
00262   // Populate acceleration limits
00263   ptr->linear_accel  = overflowSaturation(ulc_cmd_.linear_accel,  0, UINT8_MAX, 0.02, "Linear accel limit",  "m/s^2");
00264   ptr->linear_decel  = overflowSaturation(ulc_cmd_.linear_decel,  0, UINT8_MAX, 0.02, "Linear decel limit",  "m/s^2");
00265   ptr->lateral_accel = overflowSaturation(ulc_cmd_.lateral_accel, 0, UINT8_MAX, 0.05, "Lateral accel limit", "m/s^2");
00266   ptr->angular_accel = overflowSaturation(ulc_cmd_.angular_accel, 0, UINT8_MAX, 0.02, "Angular accel limit", "rad/s^2");
00267 
00268   // Publish message
00269   pub_can_.publish(msg);
00270 
00271   // Reset timer
00272   config_timer_.stop();
00273   config_timer_.start();
00274 }
00275 
00276 void UlcNode::configTimerCb(const ros::TimerEvent& event)
00277 {
00278   // Retransmit config message while command is valid
00279   if (event.current_real - cmd_stamp_ < ros::Duration(0.1)) {
00280     sendCfgMsg();
00281   }
00282 }
00283 
00284 }


dataspeed_ulc_can
Author(s): Micho Radovnikovich
autogenerated on Thu May 16 2019 03:04:21