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" 131 void cmdVelCB(
const geometry_msgs::TwistStamped::ConstPtr& msg);
132 void fanSpeedCB(
const std_msgs::Int32::ConstPtr& msg);
void robotDataMediumCB(const ros::WallTimerEvent &e)
void robotDataSlowCB(const ros::WallTimerEvent &e)
bool is_serial_coms_open_
std::vector< unsigned char > serial_fast_buffer_
void robotDataFastCB(const ros::WallTimerEvent &e)
std::vector< unsigned char > serial_slow_buffer_
void publishFastRateData()
ros::NodeHandle & nh_priv_
OdomControl left_controller_
void publishMotorSpeeds()
const int LEFT_MOTOR_INDEX_
rr_openrover_basic::SmartBatteryStatus interpret_battery_status(uint16_t bits)
ros::Publisher is_charging_pub
ros::Publisher battery_status_a_pub
int motor_speeds_commanded_[3]
void updateMeasuredVelocities()
ros::WallTimer medium_timer
int motor_speed_flipper_coef_
ros::Publisher slow_rate_pub
double right_vel_commanded_
void updateRobotData(int parameter)
bool publish_fast_rate_values_
bool publish_slow_rate_values_
const int RIGHT_MOTOR_INDEX_
double left_vel_commanded_
double right_vel_filtered_
OdomControl right_controller_
ros::Publisher battery_status_b_pub
void timeoutCB(const ros::WallTimerEvent &e)
void cmdVelCB(const geometry_msgs::TwistStamped::ConstPtr &msg)
int motor_speed_angular_coef_
int motor_speed_linear_coef_
ros::Subscriber fan_speed_sub
void publishSlowRateData()
int motor_speed_deadband_
ros::Publisher fast_rate_pub
void fanSpeedCB(const std_msgs::Int32::ConstPtr &msg)
std::vector< unsigned char > serial_fan_buffer_
float odom_traction_factor_
ros::Publisher vel_calc_pub
bool closed_loop_control_on_
ros::WallTimer slow_timer
ros::Subscriber cmd_vel_sub
ros::Publisher medium_rate_pub
std::vector< unsigned char > serial_medium_buffer_
double right_vel_measured_
ros::WallTimer timeout_timer
float odom_covariance_35_
double left_vel_measured_
ros::WallTimer fast_timer
bool sendCommand(int param1, int param2)
ros::Publisher odom_enc_pub
double left_vel_filtered_
OpenRover(ros::NodeHandle &nh, ros::NodeHandle &nh_priv)
int getParameterData(int parameter)
void publishMedRateData()
bool publish_med_rate_values_
bool setParameterData(int param1, int param2)
ros::Publisher motor_speeds_pub
void publishOdometry(float left_vel, float right_vel)
const int FLIPPER_MOTOR_INDEX_
geometry_msgs::Twist cmd_vel_commanded_
ros::Publisher battery_state_pub