openrover.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
4 #include <ros/timer.h>
5 #include <fcntl.h>
6 #include <termios.h>
7 #include <vector>
8 #include <stdint.h>
9 #include <string>
10 #include <fstream>
11 
12 #include <geometry_msgs/Twist.h>
13 #include <std_msgs/Bool.h>
14 #include "rr_openrover_driver_msgs/RawRrOpenroverDriverFastRateData.h"
15 #include "rr_openrover_driver_msgs/RawRrOpenroverDriverMedRateData.h"
16 #include "rr_openrover_driver_msgs/RawRrOpenroverDriverSlowRateData.h"
17 #include "rr_openrover_driver_msgs/SmartBatteryStatus.h"
18 
21 
22 namespace openrover
23 {
24 class OpenRover
25 {
26 public:
28 
31 
33 
34  bool start();
35  bool openComs();
36  bool setupRobotParams();
38 
39  void robotDataFastCB(const ros::WallTimerEvent& e);
41  void robotDataSlowCB(const ros::WallTimerEvent& e);
42  void timeoutCB(const ros::WallTimerEvent& e);
43 
44  void serialManager();
45 
50  bool e_stop_on_;
51 
52 private:
53  // PID debug variables
54  std::string l_pid_csv_file_;
55  std::string r_pid_csv_file_;
56  std::ofstream l_fs_;
57  std::ofstream r_fs_;
58 
59  // ROS Parameters
60  std::string port_;
61  std::string drive_type_;
62 
63  float timeout_; // Default to neutral motor values after timeout seconds
64 
65  // ROS node handlers
68 
69  // ROS Timers
74 
75  // ROS Publisher and Subscribers
81 
87 
92 
93  // General Class variables
96  int robot_data_[250]; // stores all received data from robot
98  int motor_speeds_commanded_[3]; // stores most recent commanded motor speeds
99  const int LEFT_MOTOR_INDEX_;
104  double fast_rate_hz_; // update rate for encoders, 10Hz recommended
107 
108  // drive dependent parameters
115 
116  // velocity feedback
123 
128 
129  float total_weight_; // in kg
130  // int motor_speed_diff_max_; ---WIP
131  geometry_msgs::Twist cmd_vel_commanded_;
132 
133  std::vector<unsigned char> serial_fast_buffer_;
134  std::vector<unsigned char> serial_medium_buffer_;
135  std::vector<unsigned char> serial_slow_buffer_;
136  std::vector<unsigned char> serial_fan_buffer_;
137 
138  // ROS Subscriber callback functions
139  void cmdVelCB(const geometry_msgs::Twist::ConstPtr& msg);
140  void fanSpeedCB(const std_msgs::Int32::ConstPtr& msg);
141  void eStopCB(const std_msgs::Bool::ConstPtr& msg);
142  void eStopResetCB(const std_msgs::Bool::ConstPtr& msg);
143 
144  // ROS Publish Functions (robot_data_[X] to ros topics)
145  void publishFastRateData();
146  void publishMedRateData();
147  void publishSlowRateData();
148  void publishOdometry(float left_vel, float right_vel);
149  void publishMotorSpeeds();
150  void publishWheelVels();
151 
152  // Serial Com Functions
153  int getParameterData(int parameter);
154  bool setParameterData(int param1, int param2);
155  void updateRobotData(int parameter);
156  bool sendCommand(int param1, int param2);
157  int readCommand();
158 };
159 
160 rr_openrover_driver_msgs::SmartBatteryStatus interpret_battery_status(uint16_t bits);
161 
162 } // namespace openrover
void robotDataMediumCB(const ros::WallTimerEvent &e)
void robotDataSlowCB(const ros::WallTimerEvent &e)
std::vector< unsigned char > serial_fast_buffer_
Definition: openrover.hpp:133
void robotDataFastCB(const ros::WallTimerEvent &e)
std::vector< unsigned char > serial_slow_buffer_
Definition: openrover.hpp:135
void eStopCB(const std_msgs::Bool::ConstPtr &msg)
ros::NodeHandle & nh_priv_
Definition: openrover.hpp:67
OdomControl left_controller_
Definition: openrover.hpp:29
const int LEFT_MOTOR_INDEX_
Definition: openrover.hpp:99
std::string r_pid_csv_file_
Definition: openrover.hpp:55
ros::Publisher is_charging_pub
Definition: openrover.hpp:78
void eStopResetCB(const std_msgs::Bool::ConstPtr &msg)
ros::Publisher battery_status_a_pub
Definition: openrover.hpp:85
int motor_speeds_commanded_[3]
Definition: openrover.hpp:98
std::string drive_type_
Definition: openrover.hpp:61
ros::WallTimer medium_timer
Definition: openrover.hpp:71
ros::Publisher slow_rate_pub
Definition: openrover.hpp:84
void updateRobotData(int parameter)
bool publish_fast_rate_values_
Definition: openrover.hpp:46
bool publish_slow_rate_values_
Definition: openrover.hpp:48
const int RIGHT_MOTOR_INDEX_
Definition: openrover.hpp:100
OdomControl right_controller_
Definition: openrover.hpp:30
ros::Publisher battery_status_b_pub
Definition: openrover.hpp:85
void timeoutCB(const ros::WallTimerEvent &e)
std::string l_pid_csv_file_
Definition: openrover.hpp:54
ros::Subscriber fan_speed_sub
Definition: openrover.hpp:89
std::ofstream l_fs_
Definition: openrover.hpp:56
ros::Publisher battery_state_of_charge_pub
Definition: openrover.hpp:86
ros::Publisher fast_rate_pub
Definition: openrover.hpp:82
void fanSpeedCB(const std_msgs::Int32::ConstPtr &msg)
std::vector< unsigned char > serial_fan_buffer_
Definition: openrover.hpp:136
ros::Subscriber e_stop_reset_sub
Definition: openrover.hpp:91
ros::Publisher vel_calc_pub
Definition: openrover.hpp:80
rr_openrover_driver_msgs::SmartBatteryStatus interpret_battery_status(uint16_t bits)
ros::NodeHandle & nh_
Definition: openrover.hpp:66
ros::Subscriber e_stop_sub
Definition: openrover.hpp:90
ros::WallTimer slow_timer
Definition: openrover.hpp:72
ros::Subscriber cmd_vel_sub
Definition: openrover.hpp:88
ros::Publisher medium_rate_pub
Definition: openrover.hpp:83
std::vector< unsigned char > serial_medium_buffer_
Definition: openrover.hpp:134
ros::WallTimer timeout_timer
Definition: openrover.hpp:73
ros::WallTimer fast_timer
Definition: openrover.hpp:70
bool sendCommand(int param1, int param2)
ros::Publisher odom_enc_pub
Definition: openrover.hpp:76
OpenRover(ros::NodeHandle &nh, ros::NodeHandle &nh_priv)
int getParameterData(int parameter)
bool setParameterData(int param1, int param2)
ros::Publisher motor_speeds_pub
Definition: openrover.hpp:79
void publishOdometry(float left_vel, float right_vel)
const int FLIPPER_MOTOR_INDEX_
Definition: openrover.hpp:101
geometry_msgs::Twist cmd_vel_commanded_
Definition: openrover.hpp:131
std::string port_
Definition: openrover.hpp:60
void cmdVelCB(const geometry_msgs::Twist::ConstPtr &msg)
ros::Publisher battery_state_pub
Definition: openrover.hpp:77
std::ofstream r_fs_
Definition: openrover.hpp:57


rr_openrover_driver
Author(s): Jack Kilian
autogenerated on Thu Sep 10 2020 03:38:38