Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef _DBW_NODE_H_
00036 #define _DBW_NODE_H_
00037
00038 #include <ros/ros.h>
00039
00040
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
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,
00131 JOINT_FR,
00132 JOINT_RL,
00133 JOINT_RR,
00134 JOINT_SL,
00135 JOINT_SR,
00136 JOINT_COUNT,
00137 };
00138 sensor_msgs::JointState joint_state_;
00139 void publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering);
00140
00141
00142 template <typename T> static int sgn(T val) {
00143 return ((T)0 < val) - (val < (T)0);
00144 }
00145
00146
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
00153 std::string vin_;
00154 std::string date_;
00155
00156
00157 PlatformMap firmware_;
00158
00159
00160 std::string frame_id_;
00161
00162
00163 bool warn_cmds_;
00164
00165
00166 bool buttons_;
00167
00168
00169 bool pedal_luts_;
00170
00171
00172 double acker_wheelbase_;
00173 double acker_track_;
00174 double steering_ratio_;
00175 double wheel_radius_;
00176
00177
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
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 }
00206
00207 #endif // _DBW_NODE_H_
00208