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 <dataspeed_can_msg_filters/ApproximateTime.h>
00043 #include <dbw_mkz_msgs/BrakeCmd.h>
00044 #include <dbw_mkz_msgs/BrakeReport.h>
00045 #include <dbw_mkz_msgs/ThrottleCmd.h>
00046 #include <dbw_mkz_msgs/ThrottleReport.h>
00047 #include <dbw_mkz_msgs/SteeringCmd.h>
00048 #include <dbw_mkz_msgs/SteeringReport.h>
00049 #include <dbw_mkz_msgs/GearCmd.h>
00050 #include <dbw_mkz_msgs/GearReport.h>
00051 #include <dbw_mkz_msgs/TurnSignalCmd.h>
00052 #include <dbw_mkz_msgs/Misc1Report.h>
00053 #include <dbw_mkz_msgs/WheelPositionReport.h>
00054 #include <dbw_mkz_msgs/WheelSpeedReport.h>
00055 #include <dbw_mkz_msgs/FuelLevelReport.h>
00056 #include <dbw_mkz_msgs/TirePressureReport.h>
00057 #include <dbw_mkz_msgs/SurroundReport.h>
00058 #include <dbw_mkz_msgs/BrakeInfoReport.h>
00059 #include <dbw_mkz_msgs/ThrottleInfoReport.h>
00060 #include <dbw_mkz_msgs/DriverAssistReport.h>
00061 #include <sensor_msgs/Imu.h>
00062 #include <sensor_msgs/NavSatFix.h>
00063 #include <sensor_msgs/TimeReference.h>
00064 #include <sensor_msgs/JointState.h>
00065 #include <sensor_msgs/PointCloud2.h>
00066 #include <geometry_msgs/TwistStamped.h>
00067 #include <std_msgs/Empty.h>
00068 #include <std_msgs/Bool.h>
00069 #include <std_msgs/String.h>
00070
00071
00072 #include <dbw_mkz_can/PlatformMap.h>
00073
00074 namespace dbw_mkz_can
00075 {
00076
00077 class DbwNode
00078 {
00079 public:
00080 DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh);
00081 ~DbwNode();
00082
00083 private:
00084 void timerCallback(const ros::TimerEvent& event);
00085 void recvEnable(const std_msgs::Empty::ConstPtr& msg);
00086 void recvDisable(const std_msgs::Empty::ConstPtr& msg);
00087 void recvCAN(const can_msgs::Frame::ConstPtr& msg);
00088 void recvCanImu(const std::vector<can_msgs::Frame::ConstPtr> &msgs);
00089 void recvCanGps(const std::vector<can_msgs::Frame::ConstPtr> &msgs);
00090 void recvBrakeCmd(const dbw_mkz_msgs::BrakeCmd::ConstPtr& msg);
00091 void recvThrottleCmd(const dbw_mkz_msgs::ThrottleCmd::ConstPtr& msg);
00092 void recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr& msg);
00093 void recvGearCmd(const dbw_mkz_msgs::GearCmd::ConstPtr& msg);
00094 void recvTurnSignalCmd(const dbw_mkz_msgs::TurnSignalCmd::ConstPtr& msg);
00095
00096 ros::Timer timer_;
00097 bool prev_enable_;
00098 bool enable_;
00099 bool override_brake_;
00100 bool override_throttle_;
00101 bool override_steering_;
00102 bool override_gear_;
00103 bool fault_brakes_;
00104 bool fault_throttle_;
00105 bool fault_steering_;
00106 bool fault_steering_cal_;
00107 bool fault_watchdog_;
00108 bool fault_watchdog_using_brakes_;
00109 bool fault_watchdog_warned_;
00110 bool timeout_brakes_;
00111 bool timeout_throttle_;
00112 bool timeout_steering_;
00113 bool enabled_brakes_;
00114 bool enabled_throttle_;
00115 bool enabled_steering_;
00116 bool gear_warned_;
00117 inline bool fault() { return fault_brakes_ || fault_throttle_ || fault_steering_ || fault_steering_cal_ || fault_watchdog_; }
00118 inline bool override() { return override_brake_ || override_throttle_ || override_steering_ || override_gear_; }
00119 inline bool clear() { return enable_ && override(); }
00120 inline bool enabled() { return enable_ && !fault() && !override(); }
00121 bool publishDbwEnabled();
00122 void enableSystem();
00123 void disableSystem();
00124 void buttonCancel();
00125 void overrideBrake(bool override, bool timeout);
00126 void overrideThrottle(bool override, bool timeout);
00127 void overrideSteering(bool override, bool timeout);
00128 void overrideGear(bool override);
00129 void timeoutBrake(bool timeout, bool enabled);
00130 void timeoutThrottle(bool timeout, bool enabled);
00131 void timeoutSteering(bool timeout, bool enabled);
00132 void faultBrakes(bool fault);
00133 void faultThrottle(bool fault);
00134 void faultSteering(bool fault);
00135 void faultSteeringCal(bool fault);
00136 void faultWatchdog(bool fault, uint8_t src, bool braking);
00137 void faultWatchdog(bool fault, uint8_t src = 0);
00138
00139 enum {
00140 JOINT_FL = 0,
00141 JOINT_FR,
00142 JOINT_RL,
00143 JOINT_RR,
00144 JOINT_SL,
00145 JOINT_SR,
00146 JOINT_COUNT,
00147 };
00148 sensor_msgs::JointState joint_state_;
00149 void publishJointStates(const ros::Time &stamp, const dbw_mkz_msgs::WheelSpeedReport *wheels, const dbw_mkz_msgs::SteeringReport *steering);
00150
00151
00152 template <typename T> static int sgn(T val) {
00153 return ((T)0 < val) - (val < (T)0);
00154 }
00155
00156
00157 float speedSign() const {
00158 return sgn(joint_state_.velocity[JOINT_FL]) + sgn(joint_state_.velocity[JOINT_FR]) +
00159 sgn(joint_state_.velocity[JOINT_RL]) + sgn(joint_state_.velocity[JOINT_RR]) < 0 ? -1.0 : 1.0;
00160 }
00161
00162
00163 std::string vin_;
00164 std::string date_;
00165
00166
00167 PlatformMap firmware_;
00168
00169
00170 std::string frame_id_;
00171
00172
00173 bool warn_cmds_;
00174
00175
00176 bool buttons_;
00177
00178
00179 bool pedal_luts_;
00180
00181
00182 double acker_wheelbase_;
00183 double acker_track_;
00184 double steering_ratio_;
00185
00186
00187 ros::Subscriber sub_enable_;
00188 ros::Subscriber sub_disable_;
00189 ros::Subscriber sub_can_;
00190 ros::Subscriber sub_brake_;
00191 ros::Subscriber sub_throttle_;
00192 ros::Subscriber sub_steering_;
00193 ros::Subscriber sub_gear_;
00194 ros::Subscriber sub_turn_signal_;
00195
00196
00197 ros::Publisher pub_can_;
00198 ros::Publisher pub_brake_;
00199 ros::Publisher pub_throttle_;
00200 ros::Publisher pub_steering_;
00201 ros::Publisher pub_gear_;
00202 ros::Publisher pub_misc_1_;
00203 ros::Publisher pub_wheel_speeds_;
00204 ros::Publisher pub_wheel_positions_;
00205 ros::Publisher pub_tire_pressure_;
00206 ros::Publisher pub_fuel_level_;
00207 ros::Publisher pub_surround_;
00208 ros::Publisher pub_sonar_cloud_;
00209 ros::Publisher pub_brake_info_;
00210 ros::Publisher pub_throttle_info_;
00211 ros::Publisher pub_driver_assist_;
00212 ros::Publisher pub_imu_;
00213 ros::Publisher pub_gps_fix_;
00214 ros::Publisher pub_gps_vel_;
00215 ros::Publisher pub_gps_time_;
00216 ros::Publisher pub_joint_states_;
00217 ros::Publisher pub_twist_;
00218 ros::Publisher pub_vin_;
00219 ros::Publisher pub_sys_enable_;
00220
00221
00222 dataspeed_can_msg_filters::ApproximateTime sync_imu_;
00223 dataspeed_can_msg_filters::ApproximateTime sync_gps_;
00224 };
00225
00226 }
00227
00228 #endif // _DBW_NODE_H_
00229