DbwNode.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-2019, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef _DBW_NODE_H_
36 #define _DBW_NODE_H_
37 
38 #include <ros/ros.h>
39 
40 // ROS messages
41 #include <can_msgs/Frame.h>
43 #include <dbw_mkz_msgs/BrakeCmd.h>
44 #include <dbw_mkz_msgs/BrakeReport.h>
45 #include <dbw_mkz_msgs/ThrottleCmd.h>
46 #include <dbw_mkz_msgs/ThrottleReport.h>
47 #include <dbw_mkz_msgs/SteeringCmd.h>
48 #include <dbw_mkz_msgs/SteeringReport.h>
49 #include <dbw_mkz_msgs/GearCmd.h>
50 #include <dbw_mkz_msgs/GearReport.h>
51 #include <dbw_mkz_msgs/MiscCmd.h>
52 #include <dbw_mkz_msgs/Misc1Report.h>
53 #include <dbw_mkz_msgs/WheelPositionReport.h>
54 #include <dbw_mkz_msgs/WheelSpeedReport.h>
55 #include <dbw_mkz_msgs/FuelLevelReport.h>
56 #include <dbw_mkz_msgs/TirePressureReport.h>
57 #include <dbw_mkz_msgs/SurroundReport.h>
58 #include <dbw_mkz_msgs/BrakeInfoReport.h>
59 #include <dbw_mkz_msgs/ThrottleInfoReport.h>
60 #include <dbw_mkz_msgs/DriverAssistReport.h>
61 #include <sensor_msgs/Imu.h>
62 #include <sensor_msgs/NavSatFix.h>
63 #include <sensor_msgs/TimeReference.h>
64 #include <sensor_msgs/JointState.h>
65 #include <sensor_msgs/PointCloud2.h>
66 #include <geometry_msgs/TwistStamped.h>
67 #include <std_msgs/Empty.h>
68 #include <std_msgs/Bool.h>
69 #include <std_msgs/String.h>
70 
71 // Platform and module version map
73 
74 namespace dbw_mkz_can
75 {
76 
77 class DbwNode
78 {
79 public:
81  ~DbwNode();
82 
83 private:
84  void timerCallback(const ros::TimerEvent& event);
85  void recvEnable(const std_msgs::Empty::ConstPtr& msg);
86  void recvDisable(const std_msgs::Empty::ConstPtr& msg);
87  void recvCAN(const can_msgs::Frame::ConstPtr& msg);
88  void recvCanImu(const std::vector<can_msgs::Frame::ConstPtr> &msgs);
89  void recvCanGps(const std::vector<can_msgs::Frame::ConstPtr> &msgs);
90  void recvBrakeCmd(const dbw_mkz_msgs::BrakeCmd::ConstPtr& msg);
91  void recvThrottleCmd(const dbw_mkz_msgs::ThrottleCmd::ConstPtr& msg);
92  void recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr& msg);
93  void recvGearCmd(const dbw_mkz_msgs::GearCmd::ConstPtr& msg);
94  void recvMiscCmd(const dbw_mkz_msgs::MiscCmd::ConstPtr& msg);
95 
97  bool prev_enable_;
98  bool enable_;
99  bool override_brake_;
100  bool override_throttle_;
101  bool override_steering_;
102  bool override_gear_;
103  bool fault_brakes_;
104  bool fault_throttle_;
105  bool fault_steering_;
106  bool fault_steering_cal_;
107  bool fault_watchdog_;
110  bool timeout_brakes_;
111  bool timeout_throttle_;
112  bool timeout_steering_;
113  bool enabled_brakes_;
114  bool enabled_throttle_;
115  bool enabled_steering_;
116  bool gear_warned_;
118  inline bool override() { return override_brake_ || override_throttle_ || override_steering_ || override_gear_; }
119  inline bool clear() { return enable_ && override(); }
120  inline bool enabled() { return enable_ && !fault() && !override(); }
121  bool publishDbwEnabled(bool force = false);
122  void enableSystem();
123  void disableSystem();
124  void buttonCancel();
125  void overrideBrake(bool override, bool timeout);
126  void overrideThrottle(bool override, bool timeout);
127  void overrideSteering(bool override, bool timeout);
128  void overrideGear(bool override);
129  void timeoutBrake(bool timeout, bool enabled);
130  void timeoutThrottle(bool timeout, bool enabled);
131  void timeoutSteering(bool timeout, bool enabled);
132  void faultBrakes(bool fault);
133  void faultThrottle(bool fault);
134  void faultSteering(bool fault);
135  void faultSteeringCal(bool fault);
136  void faultWatchdog(bool fault, uint8_t src, bool braking);
137  void faultWatchdog(bool fault, uint8_t src = 0);
138 
139  enum {
140  JOINT_FL = 0, // Front left wheel
141  JOINT_FR, // Front right wheel
142  JOINT_RL, // Rear left wheel
143  JOINT_RR, // Rear right wheel
144  JOINT_SL, // Steering left
145  JOINT_SR, // Steering right
146  JOINT_COUNT, // Number of joints
147  };
148  sensor_msgs::JointState joint_state_;
149  void publishJointStates(const ros::Time &stamp, const dbw_mkz_msgs::WheelSpeedReport *wheels, const dbw_mkz_msgs::SteeringReport *steering);
150 
151  // The signum function: https://stackoverflow.com/questions/1903954/
152  template <typename T> static int sgn(T val) {
153  return ((T)0 < val) - (val < (T)0);
154  }
155 
156  // Licensing
157  std::string vin_;
158  std::string ldate_; // license date
159  std::map<uint8_t, std::string> bdate_;
160 
161  // Firmware Versions
163 
164  // Frame ID
165  std::string frame_id_;
166 
167  // Command warnings
169 
170  // Buttons (enable/disable)
171  bool buttons_;
172 
173  // Pedal LUTs (local/embedded)
175 
176  // Ackermann steering
178  double acker_track_;
180 
181  // Joint states (enable/disable)
183 
184  // Subscribed topics
194 
195  // Published topics
219 
220  // Time Synchronization
223 };
224 
225 } // namespace dbw_mkz_can
226 
227 #endif // _DBW_NODE_H_
228 
dbw_mkz_can::DbwNode::ldate_
std::string ldate_
Definition: DbwNode.h:222
dbw_mkz_can::DbwNode::enable_
bool enable_
Definition: DbwNode.h:162
dbw_mkz_can::DbwNode::pub_vin_
ros::Publisher pub_vin_
Definition: DbwNode.h:281
dbw_mkz_can::DbwNode::sub_gear_
ros::Subscriber sub_gear_
Definition: DbwNode.h:255
dbw_mkz_can::DbwNode::fault_throttle_
bool fault_throttle_
Definition: DbwNode.h:168
dbw_mkz_can::DbwNode::fault_steering_
bool fault_steering_
Definition: DbwNode.h:169
dbw_mkz_can::DbwNode::prev_enable_
bool prev_enable_
Definition: DbwNode.h:161
dbw_mkz_can::DbwNode::acker_track_
double acker_track_
Definition: DbwNode.h:242
ros::Publisher
dbw_mkz_can::DbwNode::faultSteeringCal
void faultSteeringCal(bool fault)
Definition: DbwNode.cpp:1524
dbw_mkz_can::PlatformMap
Definition: PlatformMap.h:81
dbw_mkz_can::DbwNode::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: DbwNode.cpp:1282
dbw_mkz_can::DbwNode::recvSteeringCmd
void recvSteeringCmd(const dbw_mkz_msgs::SteeringCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1187
dbw_mkz_can::DbwNode::pub_gps_vel_
ros::Publisher pub_gps_vel_
Definition: DbwNode.h:277
dbw_mkz_can::DbwNode::sub_brake_
ros::Subscriber sub_brake_
Definition: DbwNode.h:252
dbw_mkz_can::DbwNode::sync_gps_
dataspeed_can_msg_filters::ApproximateTime sync_gps_
Definition: DbwNode.h:286
dbw_mkz_can::DbwNode::sub_can_
ros::Subscriber sub_can_
Definition: DbwNode.h:251
dbw_mkz_can::DbwNode::pub_gps_fix_
ros::Publisher pub_gps_fix_
Definition: DbwNode.h:276
ros.h
dbw_mkz_can::DbwNode::timeoutThrottle
void timeoutThrottle(bool timeout, bool enabled)
Definition: DbwNode.cpp:1458
dbw_mkz_can::DbwNode::pub_can_
ros::Publisher pub_can_
Definition: DbwNode.h:260
dbw_mkz_can::DbwNode::fault_watchdog_warned_
bool fault_watchdog_warned_
Definition: DbwNode.h:173
dbw_mkz_can::DbwNode::publishDbwEnabled
bool publishDbwEnabled(bool force=false)
Definition: DbwNode.cpp:1269
dbw_mkz_can::DbwNode::JOINT_FR
@ JOINT_FR
Definition: DbwNode.h:205
dbw_mkz_can::DbwNode::JOINT_SR
@ JOINT_SR
Definition: DbwNode.h:209
dbw_mkz_can::DbwNode::timeout_brakes_
bool timeout_brakes_
Definition: DbwNode.h:174
dbw_mkz_can::DbwNode::pub_throttle_
ros::Publisher pub_throttle_
Definition: DbwNode.h:262
dbw_mkz_can::DbwNode::recvDisable
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:239
dbw_mkz_can::DbwNode::DbwNode
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: DbwNode.cpp:117
dbw_mkz_can::DbwNode::timeoutBrake
void timeoutBrake(bool timeout, bool enabled)
Definition: DbwNode.cpp:1449
dbw_mkz_can::DbwNode::pub_brake_
ros::Publisher pub_brake_
Definition: DbwNode.h:261
dbw_mkz_can::DbwNode::bdate_
std::map< uint8_t, std::string > bdate_
Definition: DbwNode.h:223
dbw_mkz_can::DbwNode::faultThrottle
void faultThrottle(bool fault)
Definition: DbwNode.cpp:1492
dbw_mkz_can::DbwNode::disableSystem
void disableSystem()
Definition: DbwNode.cpp:1358
dbw_mkz_can::DbwNode::pub_driver_assist_
ros::Publisher pub_driver_assist_
Definition: DbwNode.h:274
dbw_mkz_can::DbwNode::recvEnable
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:234
dbw_mkz_can::DbwNode::sub_disable_
ros::Subscriber sub_disable_
Definition: DbwNode.h:250
dbw_mkz_can::DbwNode::override_throttle_
bool override_throttle_
Definition: DbwNode.h:164
dbw_mkz_can::DbwNode::acker_wheelbase_
double acker_wheelbase_
Definition: DbwNode.h:241
dbw_mkz_can::DbwNode::recvCanGps
void recvCanGps(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:967
dbw_mkz_can::DbwNode::publishJointStates
void publishJointStates(const ros::Time &stamp, const dbw_mkz_msgs::WheelSpeedReport *wheels, const dbw_mkz_msgs::SteeringReport *steering)
Definition: DbwNode.cpp:1621
dbw_mkz_can::DbwNode::buttonCancel
void buttonCancel()
Definition: DbwNode.cpp:1367
dbw_mkz_can::DbwNode::pub_surround_
ros::Publisher pub_surround_
Definition: DbwNode.h:270
dbw_mkz_can::DbwNode::recvGearCmd
void recvGearCmd(const dbw_mkz_msgs::GearCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1237
dbw_mkz_can::DbwNode::recvCanImu
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:921
dbw_mkz_can::DbwNode::pub_steering_
ros::Publisher pub_steering_
Definition: DbwNode.h:263
dbw_mkz_can::DbwNode::enabled
bool enabled()
Definition: DbwNode.h:184
dbw_mkz_can::DbwNode::sub_enable_
ros::Subscriber sub_enable_
Definition: DbwNode.h:249
dbw_mkz_can::DbwNode::JOINT_COUNT
@ JOINT_COUNT
Definition: DbwNode.h:210
dbw_mkz_can::DbwNode::overrideGear
void overrideGear(bool override)
Definition: DbwNode.cpp:1433
dbw_mkz_can::DbwNode::override_steering_
bool override_steering_
Definition: DbwNode.h:165
dbw_mkz_can::DbwNode::pedal_luts_
bool pedal_luts_
Definition: DbwNode.h:238
dbw_mkz_can::DbwNode::pub_gear_
ros::Publisher pub_gear_
Definition: DbwNode.h:264
dbw_mkz_can::DbwNode::pub_fuel_level_
ros::Publisher pub_fuel_level_
Definition: DbwNode.h:269
dbw_mkz_can::DbwNode::sub_misc_
ros::Subscriber sub_misc_
Definition: DbwNode.h:257
dbw_mkz_can::DbwNode::fault_brakes_
bool fault_brakes_
Definition: DbwNode.h:167
dbw_mkz_can::DbwNode::enabled_steering_
bool enabled_steering_
Definition: DbwNode.h:179
dbw_mkz_can::DbwNode::overrideThrottle
void overrideThrottle(bool override, bool timeout)
Definition: DbwNode.cpp:1395
dbw_mkz_can::DbwNode::recvBrakeCmd
void recvBrakeCmd(const dbw_mkz_msgs::BrakeCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1035
dbw_mkz_can::DbwNode::firmware_
PlatformMap firmware_
Definition: DbwNode.h:226
dbw_mkz_can::DbwNode::timer_
ros::Timer timer_
Definition: DbwNode.h:160
dbw_mkz_can::DbwNode::recvMiscCmd
void recvMiscCmd(const dbw_mkz_msgs::MiscCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1254
dbw_mkz_can::DbwNode::fault_watchdog_
bool fault_watchdog_
Definition: DbwNode.h:171
dbw_mkz_can::DbwNode::pub_wheel_speeds_
ros::Publisher pub_wheel_speeds_
Definition: DbwNode.h:266
dbw_mkz_can::DbwNode::gear_warned_
bool gear_warned_
Definition: DbwNode.h:180
dbw_mkz_can::DbwNode::pub_sonar_cloud_
ros::Publisher pub_sonar_cloud_
Definition: DbwNode.h:271
dbw_mkz_can::DbwNode::recvCAN
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: DbwNode.cpp:244
dbw_mkz_can::DbwNode::faultBrakes
void faultBrakes(bool fault)
Definition: DbwNode.cpp:1476
dbw_mkz_can::DbwNode::enabled_brakes_
bool enabled_brakes_
Definition: DbwNode.h:177
dbw_mkz_can::DbwNode::vin_
std::string vin_
Definition: DbwNode.h:221
dbw_mkz_can::DbwNode::clear
bool clear()
Definition: DbwNode.h:183
dbw_mkz_can::DbwNode::joint_state_
sensor_msgs::JointState joint_state_
Definition: DbwNode.h:212
dbw_mkz_can::DbwNode::pub_brake_info_
ros::Publisher pub_brake_info_
Definition: DbwNode.h:272
dbw_mkz_can::DbwNode::JOINT_SL
@ JOINT_SL
Definition: DbwNode.h:208
dbw_mkz_can::DbwNode::pub_imu_
ros::Publisher pub_imu_
Definition: DbwNode.h:275
ros::TimerEvent
dbw_mkz_can::DbwNode::steering_ratio_
double steering_ratio_
Definition: DbwNode.h:243
ApproximateTime.h
dbw_mkz_can::DbwNode::enableSystem
void enableSystem()
Definition: DbwNode.cpp:1328
dbw_mkz_can
Definition: dispatch.h:39
dbw_mkz_can::DbwNode::fault
bool fault()
Definition: DbwNode.h:181
dbw_mkz_can::DbwNode::faultWatchdog
void faultWatchdog(bool fault, uint8_t src, bool braking)
Definition: DbwNode.cpp:1540
PlatformMap.h
dbw_mkz_can::DbwNode::frame_id_
std::string frame_id_
Definition: DbwNode.h:229
dbw_mkz_can::DbwNode::JOINT_RR
@ JOINT_RR
Definition: DbwNode.h:207
dbw_mkz_can::DbwNode::buttons_
bool buttons_
Definition: DbwNode.h:235
dbw_mkz_can::DbwNode::enable_joint_states_
bool enable_joint_states_
Definition: DbwNode.h:246
dbw_mkz_can::DbwNode::overrideSteering
void overrideSteering(bool override, bool timeout)
Definition: DbwNode.cpp:1414
dbw_mkz_can::DbwNode::warn_cmds_
bool warn_cmds_
Definition: DbwNode.h:232
ros::Time
dbw_mkz_can::DbwNode::pub_misc_1_
ros::Publisher pub_misc_1_
Definition: DbwNode.h:265
dbw_mkz_can::DbwNode::timeout_throttle_
bool timeout_throttle_
Definition: DbwNode.h:175
dbw_mkz_can::DbwNode::sub_steering_
ros::Subscriber sub_steering_
Definition: DbwNode.h:254
dbw_mkz_can::DbwNode::sgn
static int sgn(T val)
Definition: DbwNode.h:216
dbw_mkz_can::DbwNode::override_gear_
bool override_gear_
Definition: DbwNode.h:166
dbw_mkz_can::DbwNode::timeout_steering_
bool timeout_steering_
Definition: DbwNode.h:176
dbw_mkz_can::DbwNode::enabled_throttle_
bool enabled_throttle_
Definition: DbwNode.h:178
dbw_mkz_can::DbwNode::pub_throttle_info_
ros::Publisher pub_throttle_info_
Definition: DbwNode.h:273
dbw_mkz_can::DbwNode::sub_turn_signal_
ros::Subscriber sub_turn_signal_
Definition: DbwNode.h:256
dbw_mkz_can::DbwNode::sync_imu_
dataspeed_can_msg_filters::ApproximateTime sync_imu_
Definition: DbwNode.h:285
dbw_mkz_can::DbwNode::JOINT_RL
@ JOINT_RL
Definition: DbwNode.h:206
dbw_mkz_can::DbwNode::pub_sys_enable_
ros::Publisher pub_sys_enable_
Definition: DbwNode.h:282
dbw_mkz_can::DbwNode::timeoutSteering
void timeoutSteering(bool timeout, bool enabled)
Definition: DbwNode.cpp:1467
dbw_mkz_can::DbwNode::override_brake_
bool override_brake_
Definition: DbwNode.h:163
dbw_mkz_can::DbwNode::pub_gps_time_
ros::Publisher pub_gps_time_
Definition: DbwNode.h:278
dbw_mkz_can::DbwNode::pub_wheel_positions_
ros::Publisher pub_wheel_positions_
Definition: DbwNode.h:267
dbw_mkz_can::DbwNode::overrideBrake
void overrideBrake(bool override, bool timeout)
Definition: DbwNode.cpp:1376
dbw_mkz_can::DbwNode::JOINT_FL
@ JOINT_FL
Definition: DbwNode.h:204
dbw_mkz_can::DbwNode::pub_joint_states_
ros::Publisher pub_joint_states_
Definition: DbwNode.h:279
dbw_mkz_can::DbwNode::pub_twist_
ros::Publisher pub_twist_
Definition: DbwNode.h:280
dbw_mkz_can::DbwNode::recvThrottleCmd
void recvThrottleCmd(const dbw_mkz_msgs::ThrottleCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1142
ros::Timer
dbw_mkz_can::DbwNode::pub_tire_pressure_
ros::Publisher pub_tire_pressure_
Definition: DbwNode.h:268
dbw_mkz_can::DbwNode::sub_throttle_
ros::Subscriber sub_throttle_
Definition: DbwNode.h:253
brake_sweep.node
node
Definition: brake_sweep.py:159
dataspeed_can_msg_filters::ApproximateTime
ros::NodeHandle
ros::Subscriber
dbw_mkz_can::DbwNode::~DbwNode
~DbwNode()
Definition: DbwNode.cpp:230
dbw_mkz_can::DbwNode::fault_steering_cal_
bool fault_steering_cal_
Definition: DbwNode.h:170
dbw_mkz_can::DbwNode::fault_watchdog_using_brakes_
bool fault_watchdog_using_brakes_
Definition: DbwNode.h:172
dbw_mkz_can::DbwNode::faultSteering
void faultSteering(bool fault)
Definition: DbwNode.cpp:1508


dbw_mkz_can
Author(s): Kevin Hallenbeck
autogenerated on Thu Jan 4 2024 03:46:24