DbwNode.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, 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_polaris_msgs/BrakeCmd.h>
44 #include <dbw_polaris_msgs/BrakeReport.h>
45 #include <dbw_polaris_msgs/ThrottleCmd.h>
46 #include <dbw_polaris_msgs/ThrottleReport.h>
47 #include <dbw_polaris_msgs/SteeringCmd.h>
48 #include <dbw_polaris_msgs/SteeringReport.h>
49 #include <dbw_polaris_msgs/GearCmd.h>
50 #include <dbw_polaris_msgs/GearReport.h>
51 #include <sensor_msgs/Imu.h>
52 #include <sensor_msgs/JointState.h>
53 #include <geometry_msgs/TwistStamped.h>
54 #include <std_msgs/Empty.h>
55 #include <std_msgs/Bool.h>
56 #include <std_msgs/String.h>
57 
58 // Platform and module version map
60 
61 namespace dbw_polaris_can
62 {
63 
64 class DbwNode
65 {
66 public:
67  DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh);
68  ~DbwNode();
69 
70 private:
71  void timerCallback(const ros::TimerEvent& event);
72  void recvEnable(const std_msgs::Empty::ConstPtr& msg);
73  void recvDisable(const std_msgs::Empty::ConstPtr& msg);
74  void recvCAN(const can_msgs::Frame::ConstPtr& msg);
75  void recvCanImu(const std::vector<can_msgs::Frame::ConstPtr> &msgs);
76  void recvBrakeCmd(const dbw_polaris_msgs::BrakeCmd::ConstPtr& msg);
77  void recvThrottleCmd(const dbw_polaris_msgs::ThrottleCmd::ConstPtr& msg);
78  void recvSteeringCmd(const dbw_polaris_msgs::SteeringCmd::ConstPtr& msg);
79  void recvGearCmd(const dbw_polaris_msgs::GearCmd::ConstPtr& msg);
80  void recvCalibrateSteering(const std_msgs::Empty::ConstPtr& msg);
81 
83  bool prev_enable_;
84  bool enable_;
85  bool override_brake_;
86  bool override_throttle_;
87  bool override_steering_;
88  bool override_gear_;
89  bool fault_brakes_;
90  bool fault_throttle_;
91  bool fault_steering_;
93  bool fault_watchdog_;
97  bool timeout_throttle_;
98  bool timeout_steering_;
99  bool enabled_brakes_;
100  bool enabled_throttle_;
101  bool enabled_steering_;
102  bool gear_warned_;
104  inline bool override() { return override_brake_ || override_throttle_ || override_steering_ || override_gear_; }
105  inline bool clear() { return enable_ && override(); }
106  inline bool enabled() { return enable_ && !fault() && !override(); }
107  bool publishDbwEnabled(bool force = false);
108  void enableSystem();
109  void disableSystem();
110  void buttonCancel();
111  void overrideBrake(bool override, bool timeout);
112  void overrideThrottle(bool override, bool timeout);
113  void overrideSteering(bool override, bool timeout);
114  void overrideGear(bool override);
115  void timeoutBrake(bool timeout, bool enabled);
116  void timeoutThrottle(bool timeout, bool enabled);
117  void timeoutSteering(bool timeout, bool enabled);
118  void faultBrakes(bool fault);
119  void faultThrottle(bool fault);
120  void faultSteering(bool fault);
121  void faultSteeringCal(bool fault);
122  void faultWatchdog(bool fault, uint8_t src, bool braking);
123  void faultWatchdog(bool fault, uint8_t src = 0);
124 
125  enum {
126  JOINT_FL = 0, // Front left wheel
127  JOINT_FR, // Front right wheel
128  JOINT_RL, // Rear left wheel
129  JOINT_RR, // Rear right wheel
130  JOINT_SL, // Steering left
131  JOINT_SR, // Steering right
132  JOINT_COUNT, // Number of joints
133  };
134  sensor_msgs::JointState joint_state_;
135  void publishJointStates(const ros::Time &stamp, const dbw_polaris_msgs::SteeringReport *steering);
136 
137  // The signum function: https://stackoverflow.com/questions/1903954/
138  template <typename T> static int sgn(T val) {
139  return ((T)0 < val) - (val < (T)0);
140  }
141 
142  // Licensing
143  std::string vin_;
144  std::string ldate_; // license date
145  std::map<uint8_t, std::string> bdate_;
146 
147  // Firmware Versions
149 
150  // Frame ID
151  std::string frame_id_;
152 
153  // Command warnings
155 
156  // Pedal LUTs (local/embedded)
158 
159  // Ackermann steering
161  double acker_track_;
164 
165  // Subscribed topics
174 
175  // Published topics
186 
187  // Time Synchronization
189 };
190 
191 } // namespace dbw_polaris_can
192 
193 #endif // _DBW_NODE_H_
194 
dbw_polaris_can::DbwNode::faultBrakes
void faultBrakes(bool fault)
Definition: DbwNode.cpp:943
dbw_polaris_can::DbwNode::prev_enable_
bool prev_enable_
Definition: DbwNode.h:147
dbw_polaris_can::DbwNode::JOINT_RL
@ JOINT_RL
Definition: DbwNode.h:192
dbw_polaris_can::DbwNode::override_throttle_
bool override_throttle_
Definition: DbwNode.h:150
dbw_polaris_can::DbwNode::faultSteeringCal
void faultSteeringCal(bool fault)
Definition: DbwNode.cpp:991
dbw_polaris_can::DbwNode::override_brake_
bool override_brake_
Definition: DbwNode.h:149
dbw_polaris_can::DbwNode::pub_joint_states_
ros::Publisher pub_joint_states_
Definition: DbwNode.h:246
ros::Publisher
dbw_polaris_can::DbwNode::sync_imu_
dataspeed_can_msg_filters::ApproximateTime sync_imu_
Definition: DbwNode.h:252
dbw_polaris_can::DbwNode::recvGearCmd
void recvGearCmd(const dbw_polaris_msgs::GearCmd::ConstPtr &msg)
Definition: DbwNode.cpp:703
dbw_polaris_can::DbwNode::fault_steering_
bool fault_steering_
Definition: DbwNode.h:155
dbw_polaris_can::DbwNode::pub_vin_
ros::Publisher pub_vin_
Definition: DbwNode.h:248
dbw_polaris_can::DbwNode::sub_gear_
ros::Subscriber sub_gear_
Definition: DbwNode.h:236
dbw_polaris_can::DbwNode::fault_steering_cal_
bool fault_steering_cal_
Definition: DbwNode.h:156
dbw_polaris_can::DbwNode::recvSteeringCmd
void recvSteeringCmd(const dbw_polaris_msgs::SteeringCmd::ConstPtr &msg)
Definition: DbwNode.cpp:657
dbw_polaris_can::DbwNode::sub_brake_
ros::Subscriber sub_brake_
Definition: DbwNode.h:233
dbw_polaris_can::DbwNode::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: DbwNode.cpp:749
dbw_polaris_can::DbwNode::JOINT_FL
@ JOINT_FL
Definition: DbwNode.h:190
dbw_polaris_can::DbwNode::pub_throttle_
ros::Publisher pub_throttle_
Definition: DbwNode.h:242
dbw_polaris_can::DbwNode::sub_enable_
ros::Subscriber sub_enable_
Definition: DbwNode.h:230
dbw_polaris_can::DbwNode::fault_throttle_
bool fault_throttle_
Definition: DbwNode.h:154
dbw_polaris_can::DbwNode::pedal_luts_
bool pedal_luts_
Definition: DbwNode.h:221
ros.h
dbw_polaris_can::DbwNode::buttonCancel
void buttonCancel()
Definition: DbwNode.cpp:834
dbw_polaris_can::DbwNode::disableSystem
void disableSystem()
Definition: DbwNode.cpp:825
dbw_polaris_can::DbwNode::fault_watchdog_using_brakes_
bool fault_watchdog_using_brakes_
Definition: DbwNode.h:158
dbw_polaris_can::DbwNode::joint_state_
sensor_msgs::JointState joint_state_
Definition: DbwNode.h:198
dbw_polaris_can::DbwNode::recvThrottleCmd
void recvThrottleCmd(const dbw_polaris_msgs::ThrottleCmd::ConstPtr &msg)
Definition: DbwNode.cpp:613
dbw_polaris_can::DbwNode::acker_track_
double acker_track_
Definition: DbwNode.h:225
dbw_polaris_can::PlatformMap
Definition: PlatformMap.h:81
dbw_polaris_can::DbwNode::sub_steering_
ros::Subscriber sub_steering_
Definition: DbwNode.h:235
dbw_polaris_can::DbwNode::sub_throttle_
ros::Subscriber sub_throttle_
Definition: DbwNode.h:234
dbw_polaris_can::DbwNode::override_steering_
bool override_steering_
Definition: DbwNode.h:151
dbw_polaris_can::DbwNode::sub_calibrate_steering_
ros::Subscriber sub_calibrate_steering_
Definition: DbwNode.h:237
dbw_polaris_can::DbwNode::pub_can_
ros::Publisher pub_can_
Definition: DbwNode.h:240
dbw_polaris_can::DbwNode::fault_brakes_
bool fault_brakes_
Definition: DbwNode.h:153
dbw_polaris_can::DbwNode::pub_sys_enable_
ros::Publisher pub_sys_enable_
Definition: DbwNode.h:249
dbw_polaris_can::DbwNode::timeout_steering_
bool timeout_steering_
Definition: DbwNode.h:162
dbw_polaris_can::DbwNode::fault_watchdog_warned_
bool fault_watchdog_warned_
Definition: DbwNode.h:159
dbw_polaris_can::DbwNode::gear_warned_
bool gear_warned_
Definition: DbwNode.h:166
dbw_polaris_can::DbwNode::recvBrakeCmd
void recvBrakeCmd(const dbw_polaris_msgs::BrakeCmd::ConstPtr &msg)
Definition: DbwNode.cpp:573
dbw_polaris_can::DbwNode::firmware_
PlatformMap firmware_
Definition: DbwNode.h:212
dbw_polaris_can::DbwNode::pub_twist_
ros::Publisher pub_twist_
Definition: DbwNode.h:247
dbw_polaris_can::DbwNode::recvCAN
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: DbwNode.cpp:174
dbw_polaris_can::DbwNode::~DbwNode
~DbwNode()
Definition: DbwNode.cpp:160
dbw_polaris_can::DbwNode::recvCalibrateSteering
void recvCalibrateSteering(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:720
dbw_polaris_can::DbwNode::faultWatchdog
void faultWatchdog(bool fault, uint8_t src, bool braking)
Definition: DbwNode.cpp:1007
dbw_polaris_can::DbwNode::enabled_throttle_
bool enabled_throttle_
Definition: DbwNode.h:164
dbw_polaris_can::DbwNode::faultSteering
void faultSteering(bool fault)
Definition: DbwNode.cpp:975
dbw_polaris_can::DbwNode::recvCanImu
void recvCanImu(const std::vector< can_msgs::Frame::ConstPtr > &msgs)
Definition: DbwNode.cpp:522
dbw_polaris_can::DbwNode::enable_
bool enable_
Definition: DbwNode.h:148
dbw_polaris_can::DbwNode::steering_ratio_
double steering_ratio_
Definition: DbwNode.h:226
dbw_polaris_can::DbwNode::enabled_steering_
bool enabled_steering_
Definition: DbwNode.h:165
dbw_polaris_can::DbwNode::fault_watchdog_
bool fault_watchdog_
Definition: DbwNode.h:157
dbw_polaris_can::DbwNode::faultThrottle
void faultThrottle(bool fault)
Definition: DbwNode.cpp:959
dbw_polaris_can::DbwNode::enabled
bool enabled()
Definition: DbwNode.h:170
dbw_polaris_can::DbwNode::recvEnable
void recvEnable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:164
dbw_polaris_can::DbwNode::ldate_
std::string ldate_
Definition: DbwNode.h:208
dbw_polaris_can::DbwNode::recvDisable
void recvDisable(const std_msgs::Empty::ConstPtr &msg)
Definition: DbwNode.cpp:169
dbw_polaris_can::DbwNode::pub_brake_
ros::Publisher pub_brake_
Definition: DbwNode.h:241
dbw_polaris_can::DbwNode::override_gear_
bool override_gear_
Definition: DbwNode.h:152
dbw_polaris_can::DbwNode::timeout_brakes_
bool timeout_brakes_
Definition: DbwNode.h:160
dbw_polaris_can::DbwNode::wheel_radius_
double wheel_radius_
Definition: DbwNode.h:227
ros::TimerEvent
dbw_polaris_can::DbwNode::JOINT_SR
@ JOINT_SR
Definition: DbwNode.h:195
ApproximateTime.h
dbw_polaris_can::DbwNode::bdate_
std::map< uint8_t, std::string > bdate_
Definition: DbwNode.h:209
dbw_polaris_can::DbwNode::sub_disable_
ros::Subscriber sub_disable_
Definition: DbwNode.h:231
dbw_polaris_can::DbwNode::enabled_brakes_
bool enabled_brakes_
Definition: DbwNode.h:163
dbw_polaris_can::DbwNode::frame_id_
std::string frame_id_
Definition: DbwNode.h:215
dbw_polaris_can::DbwNode::timeoutThrottle
void timeoutThrottle(bool timeout, bool enabled)
Definition: DbwNode.cpp:925
dbw_polaris_can::DbwNode::pub_steering_
ros::Publisher pub_steering_
Definition: DbwNode.h:243
PlatformMap.h
dbw_polaris_can::DbwNode::overrideSteering
void overrideSteering(bool override, bool timeout)
Definition: DbwNode.cpp:881
dbw_polaris_can::DbwNode::clear
bool clear()
Definition: DbwNode.h:169
dbw_polaris_can::DbwNode::JOINT_COUNT
@ JOINT_COUNT
Definition: DbwNode.h:196
dbw_polaris_can::DbwNode::acker_wheelbase_
double acker_wheelbase_
Definition: DbwNode.h:224
dbw_polaris_can::DbwNode::enableSystem
void enableSystem()
Definition: DbwNode.cpp:795
ros::Time
dbw_polaris_can::DbwNode::JOINT_RR
@ JOINT_RR
Definition: DbwNode.h:193
dbw_polaris_can::DbwNode::warn_cmds_
bool warn_cmds_
Definition: DbwNode.h:218
dbw_polaris_can::DbwNode::JOINT_FR
@ JOINT_FR
Definition: DbwNode.h:191
dbw_polaris_can::DbwNode::timeoutSteering
void timeoutSteering(bool timeout, bool enabled)
Definition: DbwNode.cpp:934
dbw_polaris_can::DbwNode::DbwNode
DbwNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: DbwNode.cpp:71
dbw_polaris_can::DbwNode::fault
bool fault()
Definition: DbwNode.h:167
dbw_polaris_can::DbwNode::publishDbwEnabled
bool publishDbwEnabled(bool force=false)
Definition: DbwNode.cpp:736
dbw_polaris_can::DbwNode::pub_gear_
ros::Publisher pub_gear_
Definition: DbwNode.h:244
dbw_polaris_can::DbwNode::JOINT_SL
@ JOINT_SL
Definition: DbwNode.h:194
dbw_polaris_can
Definition: dispatch.h:39
dbw_polaris_can::DbwNode::overrideThrottle
void overrideThrottle(bool override, bool timeout)
Definition: DbwNode.cpp:862
dbw_polaris_can::DbwNode::sub_can_
ros::Subscriber sub_can_
Definition: DbwNode.h:232
ros::Timer
dbw_polaris_can::DbwNode::sgn
static int sgn(T val)
Definition: DbwNode.h:202
dbw_polaris_can::DbwNode::publishJointStates
void publishJointStates(const ros::Time &stamp, const dbw_polaris_msgs::SteeringReport *steering)
Definition: DbwNode.cpp:1088
dbw_polaris_can::DbwNode::timeoutBrake
void timeoutBrake(bool timeout, bool enabled)
Definition: DbwNode.cpp:916
dataspeed_can_msg_filters::ApproximateTime
dbw_polaris_can::DbwNode::overrideBrake
void overrideBrake(bool override, bool timeout)
Definition: DbwNode.cpp:843
dbw_polaris_can::DbwNode::pub_imu_
ros::Publisher pub_imu_
Definition: DbwNode.h:245
dbw_polaris_can::DbwNode::overrideGear
void overrideGear(bool override)
Definition: DbwNode.cpp:900
ros::NodeHandle
ros::Subscriber
dbw_polaris_can::DbwNode::timeout_throttle_
bool timeout_throttle_
Definition: DbwNode.h:161
dbw_polaris_can::DbwNode::timer_
ros::Timer timer_
Definition: DbwNode.h:146
dbw_polaris_can::DbwNode::vin_
std::string vin_
Definition: DbwNode.h:207


dbw_polaris_can
Author(s): Kevin Hallenbeck
autogenerated on Thu Jan 4 2024 03:36:18