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 
11 #include <geometry_msgs/TwistStamped.h>
12 #include <std_msgs/Bool.h>
13 #include "rr_openrover_basic/RawRrOpenroverBasicFastRateData.h"
14 #include "rr_openrover_basic/RawRrOpenroverBasicMedRateData.h"
15 #include "rr_openrover_basic/RawRrOpenroverBasicSlowRateData.h"
16 #include "rr_openrover_basic/SmartBatteryStatus.h"
17 
20 
21 namespace openrover
22 {
23 class OpenRover
24 {
25 public:
27 
30 
32 
33  bool start();
34  bool openComs();
35  bool setupRobotParams();
37 
38  void robotDataFastCB(const ros::WallTimerEvent& e);
40  void robotDataSlowCB(const ros::WallTimerEvent& e);
41  void timeoutCB(const ros::WallTimerEvent& e);
42 
43  void serialManager();
44 
49  bool e_stop_on_;
50 
51 private:
52  //.csv Debugging
53  std::ofstream fs_;
54 
55  // ROS Parameters
56  std::string port_;
57  std::string drive_type_;
58 
59  float timeout_; // Default to neutral motor values after timeout seconds
60 
61  // ROS node handlers
64 
65  // ROS Timers
70 
71  // ROS Publisher and Subscribers
77 
82 
85 
86  // General Class variables
89  int robot_data_[250]; // stores all received data from robot
91  int motor_speeds_commanded_[3]; // stores most recent commanded motor speeds
92  const int LEFT_MOTOR_INDEX_;
93  const int RIGHT_MOTOR_INDEX_;
96  double fast_rate_hz_; // update rate for encoders, 10Hz recommended
98  double slow_rate_hz_;
99 
100  // drive dependent parameters
107 
108  // velocity feedback
115 
120 
121  float total_weight_; // in kg
122  // int motor_speed_diff_max_; ---WIP
123  geometry_msgs::Twist cmd_vel_commanded_;
124 
125  std::vector<unsigned char> serial_fast_buffer_;
126  std::vector<unsigned char> serial_medium_buffer_;
127  std::vector<unsigned char> serial_slow_buffer_;
128  std::vector<unsigned char> serial_fan_buffer_;
129 
130  // ROS Subscriber callback functions
131  void cmdVelCB(const geometry_msgs::TwistStamped::ConstPtr& msg);
132  void fanSpeedCB(const std_msgs::Int32::ConstPtr& msg);
133 
134  // ROS Publish Functions (robot_data_[X] to ros topics)
135  void publishFastRateData();
136  void publishMedRateData();
137  void publishSlowRateData();
138  void publishOdometry(float left_vel, float right_vel);
139  void publishMotorSpeeds();
140  void publishWheelVels();
141 
142  // Serial Com Functions
143  int getParameterData(int parameter);
144  bool setParameterData(int param1, int param2);
145  void updateRobotData(int parameter);
146  bool sendCommand(int param1, int param2);
147  int readCommand();
148 };
149 
150 rr_openrover_basic::SmartBatteryStatus interpret_battery_status(uint16_t bits);
151 
152 } // namespace openrover
void robotDataMediumCB(const ros::WallTimerEvent &e)
void robotDataSlowCB(const ros::WallTimerEvent &e)
std::vector< unsigned char > serial_fast_buffer_
Definition: openrover.hpp:125
void robotDataFastCB(const ros::WallTimerEvent &e)
std::vector< unsigned char > serial_slow_buffer_
Definition: openrover.hpp:127
ros::NodeHandle & nh_priv_
Definition: openrover.hpp:63
OdomControl left_controller_
Definition: openrover.hpp:28
const int LEFT_MOTOR_INDEX_
Definition: openrover.hpp:92
rr_openrover_basic::SmartBatteryStatus interpret_battery_status(uint16_t bits)
ros::Publisher is_charging_pub
Definition: openrover.hpp:74
ros::Publisher battery_status_a_pub
Definition: openrover.hpp:81
int motor_speeds_commanded_[3]
Definition: openrover.hpp:91
std::string drive_type_
Definition: openrover.hpp:57
std::ofstream fs_
Definition: openrover.hpp:53
ros::WallTimer medium_timer
Definition: openrover.hpp:67
ros::Publisher slow_rate_pub
Definition: openrover.hpp:80
void updateRobotData(int parameter)
bool publish_fast_rate_values_
Definition: openrover.hpp:45
bool publish_slow_rate_values_
Definition: openrover.hpp:47
const int RIGHT_MOTOR_INDEX_
Definition: openrover.hpp:93
OdomControl right_controller_
Definition: openrover.hpp:29
ros::Publisher battery_status_b_pub
Definition: openrover.hpp:81
void timeoutCB(const ros::WallTimerEvent &e)
void cmdVelCB(const geometry_msgs::TwistStamped::ConstPtr &msg)
ros::Subscriber fan_speed_sub
Definition: openrover.hpp:84
ros::Publisher fast_rate_pub
Definition: openrover.hpp:78
void fanSpeedCB(const std_msgs::Int32::ConstPtr &msg)
std::vector< unsigned char > serial_fan_buffer_
Definition: openrover.hpp:128
ros::Publisher vel_calc_pub
Definition: openrover.hpp:76
ros::NodeHandle & nh_
Definition: openrover.hpp:62
ros::WallTimer slow_timer
Definition: openrover.hpp:68
ros::Subscriber cmd_vel_sub
Definition: openrover.hpp:83
ros::Publisher medium_rate_pub
Definition: openrover.hpp:79
std::vector< unsigned char > serial_medium_buffer_
Definition: openrover.hpp:126
ros::WallTimer timeout_timer
Definition: openrover.hpp:69
ros::WallTimer fast_timer
Definition: openrover.hpp:66
bool sendCommand(int param1, int param2)
ros::Publisher odom_enc_pub
Definition: openrover.hpp:72
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:75
void publishOdometry(float left_vel, float right_vel)
const int FLIPPER_MOTOR_INDEX_
Definition: openrover.hpp:94
geometry_msgs::Twist cmd_vel_commanded_
Definition: openrover.hpp:123
std::string port_
Definition: openrover.hpp:56
ros::Publisher battery_state_pub
Definition: openrover.hpp:73


rr_openrover_basic
Author(s): Jack Kilian
autogenerated on Fri Jan 17 2020 03:18:17