DbwNode.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018-2019, 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 #ifndef _DBW_NODE_H_
00036 #define _DBW_NODE_H_
00037 
00038 #include <ros/ros.h>
00039 
00040 // ROS messages
00041 #include <can_msgs/Frame.h>
00042 #include <dbw_fca_msgs/BrakeCmd.h>
00043 #include <dbw_fca_msgs/BrakeReport.h>
00044 #include <dbw_fca_msgs/ThrottleCmd.h>
00045 #include <dbw_fca_msgs/ThrottleReport.h>
00046 #include <dbw_fca_msgs/SteeringCmd.h>
00047 #include <dbw_fca_msgs/SteeringReport.h>
00048 #include <dbw_fca_msgs/GearCmd.h>
00049 #include <dbw_fca_msgs/GearReport.h>
00050 #include <dbw_fca_msgs/TurnSignalCmd.h>
00051 #include <dbw_fca_msgs/Misc1Report.h>
00052 #include <dbw_fca_msgs/WheelPositionReport.h>
00053 #include <dbw_fca_msgs/WheelSpeedReport.h>
00054 #include <dbw_fca_msgs/FuelLevelReport.h>
00055 #include <dbw_fca_msgs/BrakeInfoReport.h>
00056 #include <dbw_fca_msgs/ThrottleInfoReport.h>
00057 #include <sensor_msgs/JointState.h>
00058 #include <geometry_msgs/TwistStamped.h>
00059 #include <std_msgs/Empty.h>
00060 #include <std_msgs/Bool.h>
00061 #include <std_msgs/String.h>
00062 
00063 // Platform and module version map
00064 #include <dbw_fca_can/PlatformMap.h>
00065 
00066 namespace dbw_fca_can
00067 {
00068 
00069 class DbwNode
00070 {
00071 public:
00072   DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh);
00073   ~DbwNode();
00074 
00075 private:
00076   void timerCallback(const ros::TimerEvent& event);
00077   void recvEnable(const std_msgs::Empty::ConstPtr& msg);
00078   void recvDisable(const std_msgs::Empty::ConstPtr& msg);
00079   void recvCAN(const can_msgs::Frame::ConstPtr& msg);
00080   void recvBrakeCmd(const dbw_fca_msgs::BrakeCmd::ConstPtr& msg);
00081   void recvThrottleCmd(const dbw_fca_msgs::ThrottleCmd::ConstPtr& msg);
00082   void recvSteeringCmd(const dbw_fca_msgs::SteeringCmd::ConstPtr& msg);
00083   void recvGearCmd(const dbw_fca_msgs::GearCmd::ConstPtr& msg);
00084   void recvTurnSignalCmd(const dbw_fca_msgs::TurnSignalCmd::ConstPtr& msg);
00085 
00086   ros::Timer timer_;
00087   bool prev_enable_;
00088   bool enable_;
00089   bool override_brake_;
00090   bool override_throttle_;
00091   bool override_steering_;
00092   bool override_gear_;
00093   bool fault_brakes_;
00094   bool fault_throttle_;
00095   bool fault_steering_;
00096   bool fault_steering_cal_;
00097   bool fault_watchdog_;
00098   bool fault_watchdog_using_brakes_;
00099   bool fault_watchdog_warned_;
00100   bool timeout_brakes_;
00101   bool timeout_throttle_;
00102   bool timeout_steering_;
00103   bool enabled_brakes_;
00104   bool enabled_throttle_;
00105   bool enabled_steering_;
00106   bool gear_warned_;
00107   inline bool fault() { return fault_brakes_ || fault_throttle_ || fault_steering_ || fault_steering_cal_ || fault_watchdog_; }
00108   inline bool override() { return override_brake_ || override_throttle_ || override_steering_ || override_gear_; }
00109   inline bool clear() { return enable_ && override(); }
00110   inline bool enabled() { return enable_ && !fault() && !override(); }
00111   bool publishDbwEnabled();
00112   void enableSystem();
00113   void disableSystem();
00114   void buttonCancel();
00115   void overrideBrake(bool override, bool timeout);
00116   void overrideThrottle(bool override, bool timeout);
00117   void overrideSteering(bool override, bool timeout);
00118   void overrideGear(bool override);
00119   void timeoutBrake(bool timeout, bool enabled);
00120   void timeoutThrottle(bool timeout, bool enabled);
00121   void timeoutSteering(bool timeout, bool enabled);
00122   void faultBrakes(bool fault);
00123   void faultThrottle(bool fault);
00124   void faultSteering(bool fault);
00125   void faultSteeringCal(bool fault);
00126   void faultWatchdog(bool fault, uint8_t src, bool braking);
00127   void faultWatchdog(bool fault, uint8_t src = 0);
00128 
00129   enum {
00130     JOINT_FL = 0, // Front left wheel
00131     JOINT_FR, // Front right wheel
00132     JOINT_RL, // Rear left wheel
00133     JOINT_RR, // Rear right wheel
00134     JOINT_SL, // Steering left
00135     JOINT_SR, // Steering right
00136     JOINT_COUNT, // Number of joints
00137   };
00138   sensor_msgs::JointState joint_state_;
00139   void publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering);
00140 
00141   // The signum function: https://stackoverflow.com/questions/1903954/
00142   template <typename T> static int sgn(T val) {
00143       return ((T)0 < val) - (val < (T)0);
00144   }
00145 
00146   // Sign of the wheel velocities, to be multiplied with vehicle speed
00147   float speedSign() const {
00148     return sgn(joint_state_.velocity[JOINT_FL]) + sgn(joint_state_.velocity[JOINT_FR]) +
00149            sgn(joint_state_.velocity[JOINT_RL]) + sgn(joint_state_.velocity[JOINT_RR]) < 0 ? -1.0 : 1.0;
00150   }
00151 
00152   // Licensing
00153   std::string vin_;
00154   std::string date_;
00155 
00156   // Firmware Versions
00157   PlatformMap firmware_;
00158 
00159   // Frame ID
00160   std::string frame_id_;
00161 
00162   // Command warnings
00163   bool warn_cmds_;
00164 
00165   // Buttons (enable/disable)
00166   bool buttons_;
00167 
00168   // Pedal LUTs (local/embedded)
00169   bool pedal_luts_;
00170 
00171   // Ackermann steering
00172   double acker_wheelbase_;
00173   double acker_track_;
00174   double steering_ratio_;
00175   double wheel_radius_;
00176 
00177   // Subscribed topics
00178   ros::Subscriber sub_enable_;
00179   ros::Subscriber sub_disable_;
00180   ros::Subscriber sub_can_;
00181   ros::Subscriber sub_brake_;
00182   ros::Subscriber sub_throttle_;
00183   ros::Subscriber sub_steering_;
00184   ros::Subscriber sub_gear_;
00185   ros::Subscriber sub_turn_signal_;
00186 
00187   // Published topics
00188   ros::Publisher pub_can_;
00189   ros::Publisher pub_brake_;
00190   ros::Publisher pub_throttle_;
00191   ros::Publisher pub_steering_;
00192   ros::Publisher pub_gear_;
00193   ros::Publisher pub_misc_1_;
00194   ros::Publisher pub_wheel_speeds_;
00195   ros::Publisher pub_wheel_positions_;
00196   ros::Publisher pub_fuel_level_;
00197   ros::Publisher pub_brake_info_;
00198   ros::Publisher pub_throttle_info_;
00199   ros::Publisher pub_joint_states_;
00200   ros::Publisher pub_twist_;
00201   ros::Publisher pub_vin_;
00202   ros::Publisher pub_sys_enable_;
00203 };
00204 
00205 } // namespace dbw_fca_can
00206 
00207 #endif // _DBW_NODE_H_
00208 


dbw_fca_can
Author(s): Kevin Hallenbeck
autogenerated on Sat May 4 2019 02:40:31