DbwNode.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018-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_fca_msgs/BrakeCmd.h>
44 #include <dbw_fca_msgs/BrakeReport.h>
45 #include <dbw_fca_msgs/ThrottleCmd.h>
46 #include <dbw_fca_msgs/ThrottleReport.h>
47 #include <dbw_fca_msgs/SteeringCmd.h>
48 #include <dbw_fca_msgs/SteeringReport.h>
49 #include <dbw_fca_msgs/GearCmd.h>
50 #include <dbw_fca_msgs/GearReport.h>
51 #include <dbw_fca_msgs/MiscCmd.h>
52 #include <dbw_fca_msgs/Misc1Report.h>
53 #include <dbw_fca_msgs/Misc2Report.h>
54 #include <dbw_fca_msgs/WheelPositionReport.h>
55 #include <dbw_fca_msgs/WheelSpeedReport.h>
56 #include <dbw_fca_msgs/FuelLevelReport.h>
57 #include <dbw_fca_msgs/TirePressureReport.h>
58 #include <dbw_fca_msgs/BrakeInfoReport.h>
59 #include <dbw_fca_msgs/ThrottleInfoReport.h>
60 #include <sensor_msgs/Imu.h>
61 #include <sensor_msgs/NavSatFix.h>
62 #include <sensor_msgs/TimeReference.h>
63 #include <sensor_msgs/JointState.h>
64 #include <geometry_msgs/TwistStamped.h>
65 #include <std_msgs/Empty.h>
66 #include <std_msgs/Bool.h>
67 #include <std_msgs/String.h>
68 
69 // Platform and module version map
71 
72 namespace dbw_fca_can
73 {
74 
75 class DbwNode
76 {
77 public:
79  ~DbwNode();
80 
81 private:
82  void timerCallback(const ros::TimerEvent& event);
83  void recvEnable(const std_msgs::Empty::ConstPtr& msg);
84  void recvDisable(const std_msgs::Empty::ConstPtr& msg);
85  void recvCAN(const can_msgs::Frame::ConstPtr& msg);
86  void recvBrakeCmd(const dbw_fca_msgs::BrakeCmd::ConstPtr& msg);
87  void recvThrottleCmd(const dbw_fca_msgs::ThrottleCmd::ConstPtr& msg);
88  void recvSteeringCmd(const dbw_fca_msgs::SteeringCmd::ConstPtr& msg);
89  void recvGearCmd(const dbw_fca_msgs::GearCmd::ConstPtr& msg);
90  void recvMiscCmd(const dbw_fca_msgs::MiscCmd::ConstPtr& msg);
91  void recvCanImu(const std::vector<can_msgs::Frame::ConstPtr> &msgs);
92  void recvCanGps(const std::vector<can_msgs::Frame::ConstPtr> &msgs);
93 
96  bool enable_;
115  inline bool fault() { return fault_brakes_ || fault_throttle_ || fault_steering_ || fault_steering_cal_ || fault_watchdog_; }
116  inline bool override() { return override_brake_ || override_throttle_ || override_steering_ || override_gear_; }
117  inline bool clear() { return enable_ && override(); }
118  inline bool enabled() { return enable_ && !fault() && !override(); }
119  bool publishDbwEnabled(bool force = false);
120  void enableSystem();
121  void disableSystem();
122  void buttonCancel();
123  void overrideBrake(bool override, bool timeout);
124  void overrideThrottle(bool override, bool timeout);
125  void overrideSteering(bool override, bool timeout);
126  void overrideGear(bool override);
127  void timeoutBrake(bool timeout, bool enabled);
128  void timeoutThrottle(bool timeout, bool enabled);
129  void timeoutSteering(bool timeout, bool enabled);
130  void faultBrakes(bool fault);
131  void faultThrottle(bool fault);
132  void faultSteering(bool fault);
133  void faultSteeringCal(bool fault);
134  void faultWatchdog(bool fault, uint8_t src, bool braking);
135  void faultWatchdog(bool fault, uint8_t src = 0);
136 
137  enum {
138  JOINT_FL = 0, // Front left wheel
139  JOINT_FR, // Front right wheel
140  JOINT_RL, // Rear left wheel
141  JOINT_RR, // Rear right wheel
142  JOINT_SL, // Steering left
143  JOINT_SR, // Steering right
144  JOINT_COUNT, // Number of joints
145  };
146  sensor_msgs::JointState joint_state_;
147  void publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering);
148 
149  // The signum function: https://stackoverflow.com/questions/1903954/
150  template <typename T> static int sgn(T val) {
151  return ((T)0 < val) - (val < (T)0);
152  }
153 
154  // Licensing
155  std::string vin_;
156  std::string ldate_; // license date
157  std::map<uint8_t, std::string> bdate_;
158 
159  // Firmware Versions
161 
162  // Frame ID
163  std::string frame_id_;
164 
165  // Command warnings
167 
168  // Buttons (enable/disable)
169  bool buttons_;
170 
171  // Pedal LUTs (local/embedded)
173 
174  // Ackermann steering
176  double acker_track_;
179 
180  // Joint states (enable/disable)
182 
183  // Subscribed topics
193 
194  // Published topics
216 
217  // Time Synchronization
220 };
221 
222 } // namespace dbw_fca_can
223 
224 #endif // _DBW_NODE_H_
225 
double steering_ratio_
Definition: DbwNode.h:177
bool fault_watchdog_warned_
Definition: DbwNode.h:107
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: DbwNode.cpp:205
ros::Publisher pub_wheel_speeds_
Definition: DbwNode.h:202
ros::Publisher pub_gps_fix_
Definition: DbwNode.h:209
void overrideThrottle(bool override, bool timeout)
Definition: DbwNode.cpp:1193
ros::Subscriber sub_turn_signal_
Definition: DbwNode.h:191
ros::Publisher pub_misc_1_
Definition: DbwNode.h:200
void faultWatchdog(bool fault, uint8_t src, bool braking)
Definition: DbwNode.cpp:1338
ros::Publisher pub_imu_
Definition: DbwNode.h:208
void recvGearCmd(const dbw_fca_msgs::GearCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1016
double acker_wheelbase_
Definition: DbwNode.h:175
void timeoutThrottle(bool timeout, bool enabled)
Definition: DbwNode.cpp:1256
static int sgn(T val)
Definition: DbwNode.h:150
ros::Publisher pub_gps_time_
Definition: DbwNode.h:210
void overrideGear(bool override)
Definition: DbwNode.cpp:1231
ros::Subscriber sub_steering_
Definition: DbwNode.h:189
ros::Subscriber sub_throttle_
Definition: DbwNode.h:188
bool enable_joint_states_
Definition: DbwNode.h:181
void recvThrottleCmd(const dbw_fca_msgs::ThrottleCmd::ConstPtr &msg)
Definition: DbwNode.cpp:925
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:755
void faultSteering(bool fault)
Definition: DbwNode.cpp:1306
ros::Subscriber sub_brake_
Definition: DbwNode.h:187
ros::Publisher pub_wheel_positions_
Definition: DbwNode.h:203
ros::Publisher pub_gps_fix_dr
Definition: DbwNode.h:211
void recvBrakeCmd(const dbw_fca_msgs::BrakeCmd::ConstPtr &msg)
Definition: DbwNode.cpp:850
std::string vin_
Definition: DbwNode.h:155
void faultSteeringCal(bool fault)
Definition: DbwNode.cpp:1322
void faultThrottle(bool fault)
Definition: DbwNode.cpp:1290
ros::Publisher pub_brake_info_
Definition: DbwNode.h:206
void recvSteeringCmd(const dbw_fca_msgs::SteeringCmd::ConstPtr &msg)
Definition: DbwNode.cpp:969
std::string frame_id_
Definition: DbwNode.h:163
ros::Subscriber sub_enable_
Definition: DbwNode.h:184
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:200
ros::Publisher pub_throttle_info_
Definition: DbwNode.h:207
bool override_throttle_
Definition: DbwNode.h:98
ros::Publisher pub_brake_
Definition: DbwNode.h:196
std::map< uint8_t, std::string > bdate_
Definition: DbwNode.h:157
ros::Subscriber sub_can_
Definition: DbwNode.h:186
sensor_msgs::JointState joint_state_
Definition: DbwNode.h:146
bool fault_watchdog_using_brakes_
Definition: DbwNode.h:106
ros::Publisher pub_can_
Definition: DbwNode.h:195
ros::Publisher pub_joint_states_
Definition: DbwNode.h:212
void timerCallback(const ros::TimerEvent &event)
Definition: DbwNode.cpp:1080
PlatformMap firmware_
Definition: DbwNode.h:160
bool fault_steering_cal_
Definition: DbwNode.h:104
dataspeed_can_msg_filters::ApproximateTime sync_gps_
Definition: DbwNode.h:219
ros::Publisher pub_sys_enable_
Definition: DbwNode.h:215
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:195
ros::Publisher pub_throttle_
Definition: DbwNode.h:197
void timeoutBrake(bool timeout, bool enabled)
Definition: DbwNode.cpp:1247
void overrideBrake(bool override, bool timeout)
Definition: DbwNode.cpp:1174
void overrideSteering(bool override, bool timeout)
Definition: DbwNode.cpp:1212
ros::Subscriber sub_gear_
Definition: DbwNode.h:190
dataspeed_can_msg_filters::ApproximateTime sync_imu_
Definition: DbwNode.h:218
bool publishDbwEnabled(bool force=false)
Definition: DbwNode.cpp:1067
void recvCanGps(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:791
void faultBrakes(bool fault)
Definition: DbwNode.cpp:1274
ros::Publisher pub_misc_2_
Definition: DbwNode.h:201
ros::Publisher pub_gear_
Definition: DbwNode.h:199
ros::Subscriber sub_disable_
Definition: DbwNode.h:185
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: DbwNode.cpp:79
bool override_steering_
Definition: DbwNode.h:99
ros::Subscriber sub_misc_
Definition: DbwNode.h:192
ros::Publisher pub_tire_pressure_
Definition: DbwNode.h:204
std::string ldate_
Definition: DbwNode.h:156
ros::Publisher pub_fuel_level_
Definition: DbwNode.h:205
ros::Timer timer_
Definition: DbwNode.h:94
void publishJointStates(const ros::Time &stamp, const dbw_fca_msgs::SteeringReport *steering)
Definition: DbwNode.cpp:1419
void recvMiscCmd(const dbw_fca_msgs::MiscCmd::ConstPtr &msg)
Definition: DbwNode.cpp:1033
void timeoutSteering(bool timeout, bool enabled)
Definition: DbwNode.cpp:1265
ros::Publisher pub_twist_
Definition: DbwNode.h:213
ros::Publisher pub_vin_
Definition: DbwNode.h:214
ros::Publisher pub_steering_
Definition: DbwNode.h:198
double wheel_radius_
Definition: DbwNode.h:178


dbw_fca_can
Author(s): Kevin Hallenbeck
autogenerated on Fri Jun 16 2023 02:36:28