Public Member Functions | Private Member Functions | Private Attributes | List of all members
CreateDriver Class Reference

#include <create_driver.h>

Public Member Functions

 CreateDriver (ros::NodeHandle &nh)
 
virtual void spin ()
 
virtual void spinOnce ()
 
 ~CreateDriver ()
 

Private Member Functions

void checkLEDCallback (const std_msgs::BoolConstPtr &msg)
 
void cmdVelCallback (const geometry_msgs::TwistConstPtr &msg)
 
void debrisLEDCallback (const std_msgs::BoolConstPtr &msg)
 
void defineSongCallback (const create_msgs::DefineSongConstPtr &msg)
 
void dockCallback (const std_msgs::EmptyConstPtr &msg)
 
void dockLEDCallback (const std_msgs::BoolConstPtr &msg)
 
void mainBrushMotor (const create_msgs::MotorSetpointConstPtr &msg)
 
void playSongCallback (const create_msgs::PlaySongConstPtr &msg)
 
void powerLEDCallback (const std_msgs::UInt8MultiArrayConstPtr &msg)
 
void publishBatteryInfo ()
 
void publishBumperInfo ()
 
void publishButtonPresses () const
 
void publishJointState ()
 
void publishMode ()
 
void publishOdom ()
 
void publishOmniChar ()
 
void publishWheeldrop ()
 
void setASCIICallback (const std_msgs::UInt8MultiArrayConstPtr &msg)
 
void sideBrushMotor (const create_msgs::MotorSetpointConstPtr &msg)
 
void spotLEDCallback (const std_msgs::BoolConstPtr &msg)
 
void undockCallback (const std_msgs::EmptyConstPtr &msg)
 
bool update ()
 
void updateBatteryDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void updateDriverDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void updateModeDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void updateSafetyDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void updateSerialDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void vacuumBrushMotor (const create_msgs::MotorSetpointConstPtr &msg)
 

Private Attributes

std::string base_frame_
 
int baud_
 
create_msgs::Bumper bumper_msg_
 
ros::Publisher bumper_pub_
 
ros::Publisher capacity_pub_
 
ros::Publisher charge_pub_
 
ros::Publisher charge_ratio_pub_
 
create_msgs::ChargingState charging_state_msg_
 
ros::Publisher charging_state_pub_
 
ros::Subscriber check_led_sub_
 
ros::Publisher clean_btn_pub_
 
ros::Subscriber cmd_vel_sub_
 
ros::Publisher current_pub_
 
ros::Publisher day_btn_pub_
 
ros::Subscriber debris_led_sub_
 
ros::Subscriber define_song_sub_
 
std::string dev_
 
diagnostic_updater::Updater diagnostics_
 
ros::Publisher dock_btn_pub_
 
ros::Subscriber dock_led_sub_
 
ros::Subscriber dock_sub_
 
std_msgs::Empty empty_msg_
 
std_msgs::Float32 float32_msg_
 
ros::Publisher hour_btn_pub_
 
std_msgs::Int16 int16_msg_
 
bool is_running_slowly_
 
sensor_msgs::JointState joint_state_msg_
 
ros::Time last_cmd_vel_time_
 
double latch_duration_
 
double loop_hz_
 
ros::Subscriber main_brush_motor_sub_
 
ros::Publisher min_btn_pub_
 
create_msgs::Mode mode_msg_
 
ros::Publisher mode_pub_
 
create::RobotModel model_
 
ros::NodeHandle nh_
 
std::string odom_frame_
 
nav_msgs::Odometry odom_msg_
 
ros::Publisher odom_pub_
 
ros::Publisher omni_char_pub_
 
ros::Subscriber play_song_sub_
 
ros::Subscriber power_led_sub_
 
ros::NodeHandle priv_nh_
 
bool publish_tf_
 
create::Createrobot_
 
ros::Subscriber set_ascii_sub_
 
ros::Subscriber side_brush_motor_sub_
 
ros::Publisher spot_btn_pub_
 
ros::Subscriber spot_led_sub_
 
ros::Publisher temperature_pub_
 
tf2_ros::TransformBroadcaster tf_broadcaster_
 
geometry_msgs::TransformStamped tf_odom_
 
std_msgs::UInt16 uint16_msg_
 
ros::Subscriber undock_sub_
 
ros::Subscriber vacuum_motor_sub_
 
ros::Publisher voltage_pub_
 
ros::Publisher wheel_joint_pub_
 
ros::Publisher wheeldrop_pub_
 

Detailed Description

Definition at line 62 of file create_driver.h.

Constructor & Destructor Documentation

◆ CreateDriver()

CreateDriver::CreateDriver ( ros::NodeHandle nh)
explicit

Definition at line 34 of file create_driver.cpp.

◆ ~CreateDriver()

CreateDriver::~CreateDriver ( )

Definition at line 160 of file create_driver.cpp.

Member Function Documentation

◆ checkLEDCallback()

void CreateDriver::checkLEDCallback ( const std_msgs::BoolConstPtr &  msg)
private

Definition at line 188 of file create_driver.cpp.

◆ cmdVelCallback()

void CreateDriver::cmdVelCallback ( const geometry_msgs::TwistConstPtr &  msg)
private

Definition at line 167 of file create_driver.cpp.

◆ debrisLEDCallback()

void CreateDriver::debrisLEDCallback ( const std_msgs::BoolConstPtr &  msg)
private

Definition at line 173 of file create_driver.cpp.

◆ defineSongCallback()

void CreateDriver::defineSongCallback ( const create_msgs::DefineSongConstPtr &  msg)
private

Definition at line 263 of file create_driver.cpp.

◆ dockCallback()

void CreateDriver::dockCallback ( const std_msgs::EmptyConstPtr &  msg)
private

Definition at line 242 of file create_driver.cpp.

◆ dockLEDCallback()

void CreateDriver::dockLEDCallback ( const std_msgs::BoolConstPtr &  msg)
private

Definition at line 183 of file create_driver.cpp.

◆ mainBrushMotor()

void CreateDriver::mainBrushMotor ( const create_msgs::MotorSetpointConstPtr &  msg)
private

Definition at line 286 of file create_driver.cpp.

◆ playSongCallback()

void CreateDriver::playSongCallback ( const create_msgs::PlaySongConstPtr &  msg)
private

Definition at line 271 of file create_driver.cpp.

◆ powerLEDCallback()

void CreateDriver::powerLEDCallback ( const std_msgs::UInt8MultiArrayConstPtr &  msg)
private

Definition at line 193 of file create_driver.cpp.

◆ publishBatteryInfo()

void CreateDriver::publishBatteryInfo ( )
private

Definition at line 518 of file create_driver.cpp.

◆ publishBumperInfo()

void CreateDriver::publishBumperInfo ( )
private

Definition at line 624 of file create_driver.cpp.

◆ publishButtonPresses()

void CreateDriver::publishButtonPresses ( ) const
private

Definition at line 563 of file create_driver.cpp.

◆ publishJointState()

void CreateDriver::publishJointState ( )
private

Definition at line 505 of file create_driver.cpp.

◆ publishMode()

void CreateDriver::publishMode ( )
private

Definition at line 599 of file create_driver.cpp.

◆ publishOdom()

void CreateDriver::publishOdom ( )
private

Definition at line 454 of file create_driver.cpp.

◆ publishOmniChar()

void CreateDriver::publishOmniChar ( )
private

Definition at line 591 of file create_driver.cpp.

◆ publishWheeldrop()

void CreateDriver::publishWheeldrop ( )
private

Definition at line 650 of file create_driver.cpp.

◆ setASCIICallback()

void CreateDriver::setASCIICallback ( const std_msgs::UInt8MultiArrayConstPtr &  msg)
private

Definition at line 212 of file create_driver.cpp.

◆ sideBrushMotor()

void CreateDriver::sideBrushMotor ( const create_msgs::MotorSetpointConstPtr &  msg)
private

Definition at line 279 of file create_driver.cpp.

◆ spin()

void CreateDriver::spin ( )
virtual

Definition at line 663 of file create_driver.cpp.

◆ spinOnce()

void CreateDriver::spinOnce ( )
virtual

Definition at line 656 of file create_driver.cpp.

◆ spotLEDCallback()

void CreateDriver::spotLEDCallback ( const std_msgs::BoolConstPtr &  msg)
private

Definition at line 178 of file create_driver.cpp.

◆ undockCallback()

void CreateDriver::undockCallback ( const std_msgs::EmptyConstPtr &  msg)
private

Definition at line 255 of file create_driver.cpp.

◆ update()

bool CreateDriver::update ( )
private

Definition at line 301 of file create_driver.cpp.

◆ updateBatteryDiagnostics()

void CreateDriver::updateBatteryDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 321 of file create_driver.cpp.

◆ updateDriverDiagnostics()

void CreateDriver::updateDriverDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 442 of file create_driver.cpp.

◆ updateModeDiagnostics()

void CreateDriver::updateModeDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 419 of file create_driver.cpp.

◆ updateSafetyDiagnostics()

void CreateDriver::updateSafetyDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 374 of file create_driver.cpp.

◆ updateSerialDiagnostics()

void CreateDriver::updateSerialDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 395 of file create_driver.cpp.

◆ vacuumBrushMotor()

void CreateDriver::vacuumBrushMotor ( const create_msgs::MotorSetpointConstPtr &  msg)
private

Definition at line 293 of file create_driver.cpp.

Member Data Documentation

◆ base_frame_

std::string CreateDriver::base_frame_
private

Definition at line 125 of file create_driver.h.

◆ baud_

int CreateDriver::baud_
private

Definition at line 130 of file create_driver.h.

◆ bumper_msg_

create_msgs::Bumper CreateDriver::bumper_msg_
private

Definition at line 112 of file create_driver.h.

◆ bumper_pub_

ros::Publisher CreateDriver::bumper_pub_
private

Definition at line 102 of file create_driver.h.

◆ capacity_pub_

ros::Publisher CreateDriver::capacity_pub_
private

Definition at line 97 of file create_driver.h.

◆ charge_pub_

ros::Publisher CreateDriver::charge_pub_
private

Definition at line 95 of file create_driver.h.

◆ charge_ratio_pub_

ros::Publisher CreateDriver::charge_ratio_pub_
private

Definition at line 96 of file create_driver.h.

◆ charging_state_msg_

create_msgs::ChargingState CreateDriver::charging_state_msg_
private

Definition at line 111 of file create_driver.h.

◆ charging_state_pub_

ros::Publisher CreateDriver::charging_state_pub_
private

Definition at line 99 of file create_driver.h.

◆ check_led_sub_

ros::Subscriber CreateDriver::check_led_sub_
private

Definition at line 75 of file create_driver.h.

◆ clean_btn_pub_

ros::Publisher CreateDriver::clean_btn_pub_
private

Definition at line 87 of file create_driver.h.

◆ cmd_vel_sub_

ros::Subscriber CreateDriver::cmd_vel_sub_
private

Definition at line 71 of file create_driver.h.

◆ current_pub_

ros::Publisher CreateDriver::current_pub_
private

Definition at line 94 of file create_driver.h.

◆ day_btn_pub_

ros::Publisher CreateDriver::day_btn_pub_
private

Definition at line 88 of file create_driver.h.

◆ debris_led_sub_

ros::Subscriber CreateDriver::debris_led_sub_
private

Definition at line 72 of file create_driver.h.

◆ define_song_sub_

ros::Subscriber CreateDriver::define_song_sub_
private

Definition at line 80 of file create_driver.h.

◆ dev_

std::string CreateDriver::dev_
private

Definition at line 124 of file create_driver.h.

◆ diagnostics_

diagnostic_updater::Updater CreateDriver::diagnostics_
private

Definition at line 108 of file create_driver.h.

◆ dock_btn_pub_

ros::Publisher CreateDriver::dock_btn_pub_
private

Definition at line 91 of file create_driver.h.

◆ dock_led_sub_

ros::Subscriber CreateDriver::dock_led_sub_
private

Definition at line 74 of file create_driver.h.

◆ dock_sub_

ros::Subscriber CreateDriver::dock_sub_
private

Definition at line 78 of file create_driver.h.

◆ empty_msg_

std_msgs::Empty CreateDriver::empty_msg_
private

Definition at line 116 of file create_driver.h.

◆ float32_msg_

std_msgs::Float32 CreateDriver::float32_msg_
private

Definition at line 117 of file create_driver.h.

◆ hour_btn_pub_

ros::Publisher CreateDriver::hour_btn_pub_
private

Definition at line 89 of file create_driver.h.

◆ int16_msg_

std_msgs::Int16 CreateDriver::int16_msg_
private

Definition at line 119 of file create_driver.h.

◆ is_running_slowly_

bool CreateDriver::is_running_slowly_
private

Definition at line 121 of file create_driver.h.

◆ joint_state_msg_

sensor_msgs::JointState CreateDriver::joint_state_msg_
private

Definition at line 120 of file create_driver.h.

◆ last_cmd_vel_time_

ros::Time CreateDriver::last_cmd_vel_time_
private

Definition at line 115 of file create_driver.h.

◆ latch_duration_

double CreateDriver::latch_duration_
private

Definition at line 127 of file create_driver.h.

◆ loop_hz_

double CreateDriver::loop_hz_
private

Definition at line 128 of file create_driver.h.

◆ main_brush_motor_sub_

ros::Subscriber CreateDriver::main_brush_motor_sub_
private

Definition at line 83 of file create_driver.h.

◆ min_btn_pub_

ros::Publisher CreateDriver::min_btn_pub_
private

Definition at line 90 of file create_driver.h.

◆ mode_msg_

create_msgs::Mode CreateDriver::mode_msg_
private

Definition at line 110 of file create_driver.h.

◆ mode_pub_

ros::Publisher CreateDriver::mode_pub_
private

Definition at line 101 of file create_driver.h.

◆ model_

create::RobotModel CreateDriver::model_
private

Definition at line 66 of file create_driver.h.

◆ nh_

ros::NodeHandle CreateDriver::nh_
private

Definition at line 68 of file create_driver.h.

◆ odom_frame_

std::string CreateDriver::odom_frame_
private

Definition at line 126 of file create_driver.h.

◆ odom_msg_

nav_msgs::Odometry CreateDriver::odom_msg_
private

Definition at line 113 of file create_driver.h.

◆ odom_pub_

ros::Publisher CreateDriver::odom_pub_
private

Definition at line 86 of file create_driver.h.

◆ omni_char_pub_

ros::Publisher CreateDriver::omni_char_pub_
private

Definition at line 100 of file create_driver.h.

◆ play_song_sub_

ros::Subscriber CreateDriver::play_song_sub_
private

Definition at line 81 of file create_driver.h.

◆ power_led_sub_

ros::Subscriber CreateDriver::power_led_sub_
private

Definition at line 76 of file create_driver.h.

◆ priv_nh_

ros::NodeHandle CreateDriver::priv_nh_
private

Definition at line 69 of file create_driver.h.

◆ publish_tf_

bool CreateDriver::publish_tf_
private

Definition at line 129 of file create_driver.h.

◆ robot_

create::Create* CreateDriver::robot_
private

Definition at line 65 of file create_driver.h.

◆ set_ascii_sub_

ros::Subscriber CreateDriver::set_ascii_sub_
private

Definition at line 77 of file create_driver.h.

◆ side_brush_motor_sub_

ros::Subscriber CreateDriver::side_brush_motor_sub_
private

Definition at line 82 of file create_driver.h.

◆ spot_btn_pub_

ros::Publisher CreateDriver::spot_btn_pub_
private

Definition at line 92 of file create_driver.h.

◆ spot_led_sub_

ros::Subscriber CreateDriver::spot_led_sub_
private

Definition at line 73 of file create_driver.h.

◆ temperature_pub_

ros::Publisher CreateDriver::temperature_pub_
private

Definition at line 98 of file create_driver.h.

◆ tf_broadcaster_

tf2_ros::TransformBroadcaster CreateDriver::tf_broadcaster_
private

Definition at line 106 of file create_driver.h.

◆ tf_odom_

geometry_msgs::TransformStamped CreateDriver::tf_odom_
private

Definition at line 114 of file create_driver.h.

◆ uint16_msg_

std_msgs::UInt16 CreateDriver::uint16_msg_
private

Definition at line 118 of file create_driver.h.

◆ undock_sub_

ros::Subscriber CreateDriver::undock_sub_
private

Definition at line 79 of file create_driver.h.

◆ vacuum_motor_sub_

ros::Subscriber CreateDriver::vacuum_motor_sub_
private

Definition at line 84 of file create_driver.h.

◆ voltage_pub_

ros::Publisher CreateDriver::voltage_pub_
private

Definition at line 93 of file create_driver.h.

◆ wheel_joint_pub_

ros::Publisher CreateDriver::wheel_joint_pub_
private

Definition at line 104 of file create_driver.h.

◆ wheeldrop_pub_

ros::Publisher CreateDriver::wheeldrop_pub_
private

Definition at line 103 of file create_driver.h.


The documentation for this class was generated from the following files:


create_driver
Author(s): Jacob Perron
autogenerated on Mon May 22 2023 02:31:38