Public Member Functions | Protected Attributes | 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 ()
 

Protected Attributes

ros::Publisher bumper_pub_
 
ros::Publisher capacity_pub_
 
ros::Publisher charge_pub_
 
ros::Publisher charge_ratio_pub_
 
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_
 
ros::Publisher dock_btn_pub_
 
ros::Subscriber dock_led_sub_
 
ros::Subscriber dock_sub_
 
ros::Publisher hour_btn_pub_
 
ros::Publisher min_btn_pub_
 
ros::Publisher mode_pub_
 
ros::NodeHandle nh_
 
ros::Publisher odom_pub_
 
ros::Publisher omni_char_pub_
 
ros::Subscriber play_song_sub_
 
ros::Subscriber power_led_sub_
 
ros::NodeHandle priv_nh_
 
ros::Subscriber set_ascii_sub_
 
ros::Publisher spot_btn_pub_
 
ros::Subscriber spot_led_sub_
 
ros::Publisher temperature_pub_
 
ros::Subscriber undock_sub_
 
ros::Publisher voltage_pub_
 
ros::Publisher wheel_joint_pub_
 
ros::Publisher wheeldrop_pub_
 

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 ca_msgs::DefineSongConstPtr &msg)
 
void dockCallback (const std_msgs::EmptyConstPtr &msg)
 
void dockLEDCallback (const std_msgs::BoolConstPtr &msg)
 
void playSongCallback (const ca_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 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)
 

Private Attributes

std::string base_frame_
 
int baud_
 
ca_msgs::Bumper bumper_msg_
 
ca_msgs::ChargingState charging_state_msg_
 
std::string dev_
 
diagnostic_updater::Updater diagnostics_
 
std_msgs::Empty empty_msg_
 
std_msgs::Float32 float32_msg_
 
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_
 
ca_msgs::Mode mode_msg_
 
create::RobotModel model_
 
std::string odom_frame_
 
nav_msgs::Odometry odom_msg_
 
bool publish_tf_
 
create::Createrobot_
 
tf::TransformBroadcaster tf_broadcaster_
 
geometry_msgs::TransformStamped tf_odom_
 
std_msgs::UInt16 uint16_msg_
 

Detailed Description

Definition at line 63 of file create_driver.h.

Constructor & Destructor Documentation

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

Definition at line 34 of file create_driver.cpp.

CreateDriver::~CreateDriver ( )

Definition at line 158 of file create_driver.cpp.

Member Function Documentation

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

Definition at line 186 of file create_driver.cpp.

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

Definition at line 165 of file create_driver.cpp.

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

Definition at line 171 of file create_driver.cpp.

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

Definition at line 257 of file create_driver.cpp.

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

Definition at line 240 of file create_driver.cpp.

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

Definition at line 181 of file create_driver.cpp.

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

Definition at line 265 of file create_driver.cpp.

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

Definition at line 191 of file create_driver.cpp.

void CreateDriver::publishBatteryInfo ( )
private

Definition at line 488 of file create_driver.cpp.

void CreateDriver::publishBumperInfo ( )
private

Definition at line 594 of file create_driver.cpp.

void CreateDriver::publishButtonPresses ( ) const
private

Definition at line 533 of file create_driver.cpp.

void CreateDriver::publishJointState ( )
private

Definition at line 475 of file create_driver.cpp.

void CreateDriver::publishMode ( )
private

Definition at line 569 of file create_driver.cpp.

void CreateDriver::publishOdom ( )
private

Definition at line 426 of file create_driver.cpp.

void CreateDriver::publishOmniChar ( )
private

Definition at line 561 of file create_driver.cpp.

void CreateDriver::publishWheeldrop ( )
private

Definition at line 620 of file create_driver.cpp.

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

Definition at line 210 of file create_driver.cpp.

void CreateDriver::spin ( )
virtual

Definition at line 633 of file create_driver.cpp.

void CreateDriver::spinOnce ( )
virtual

Definition at line 626 of file create_driver.cpp.

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

Definition at line 176 of file create_driver.cpp.

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

Definition at line 251 of file create_driver.cpp.

bool CreateDriver::update ( )
private

Definition at line 273 of file create_driver.cpp.

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

Definition at line 293 of file create_driver.cpp.

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

Definition at line 414 of file create_driver.cpp.

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

Definition at line 391 of file create_driver.cpp.

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

Definition at line 346 of file create_driver.cpp.

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

Definition at line 367 of file create_driver.cpp.

Member Data Documentation

std::string CreateDriver::base_frame_
private

Definition at line 85 of file create_driver.h.

int CreateDriver::baud_
private

Definition at line 90 of file create_driver.h.

ca_msgs::Bumper CreateDriver::bumper_msg_
private

Definition at line 72 of file create_driver.h.

ros::Publisher CreateDriver::bumper_pub_
protected

Definition at line 150 of file create_driver.h.

ros::Publisher CreateDriver::capacity_pub_
protected

Definition at line 145 of file create_driver.h.

ros::Publisher CreateDriver::charge_pub_
protected

Definition at line 143 of file create_driver.h.

ros::Publisher CreateDriver::charge_ratio_pub_
protected

Definition at line 144 of file create_driver.h.

ca_msgs::ChargingState CreateDriver::charging_state_msg_
private

Definition at line 71 of file create_driver.h.

ros::Publisher CreateDriver::charging_state_pub_
protected

Definition at line 147 of file create_driver.h.

ros::Subscriber CreateDriver::check_led_sub_
protected

Definition at line 126 of file create_driver.h.

ros::Publisher CreateDriver::clean_btn_pub_
protected

Definition at line 135 of file create_driver.h.

ros::Subscriber CreateDriver::cmd_vel_sub_
protected

Definition at line 122 of file create_driver.h.

ros::Publisher CreateDriver::current_pub_
protected

Definition at line 142 of file create_driver.h.

ros::Publisher CreateDriver::day_btn_pub_
protected

Definition at line 136 of file create_driver.h.

ros::Subscriber CreateDriver::debris_led_sub_
protected

Definition at line 123 of file create_driver.h.

ros::Subscriber CreateDriver::define_song_sub_
protected

Definition at line 131 of file create_driver.h.

std::string CreateDriver::dev_
private

Definition at line 84 of file create_driver.h.

diagnostic_updater::Updater CreateDriver::diagnostics_
private

Definition at line 69 of file create_driver.h.

ros::Publisher CreateDriver::dock_btn_pub_
protected

Definition at line 139 of file create_driver.h.

ros::Subscriber CreateDriver::dock_led_sub_
protected

Definition at line 125 of file create_driver.h.

ros::Subscriber CreateDriver::dock_sub_
protected

Definition at line 129 of file create_driver.h.

std_msgs::Empty CreateDriver::empty_msg_
private

Definition at line 76 of file create_driver.h.

std_msgs::Float32 CreateDriver::float32_msg_
private

Definition at line 77 of file create_driver.h.

ros::Publisher CreateDriver::hour_btn_pub_
protected

Definition at line 137 of file create_driver.h.

std_msgs::Int16 CreateDriver::int16_msg_
private

Definition at line 79 of file create_driver.h.

bool CreateDriver::is_running_slowly_
private

Definition at line 81 of file create_driver.h.

sensor_msgs::JointState CreateDriver::joint_state_msg_
private

Definition at line 80 of file create_driver.h.

ros::Time CreateDriver::last_cmd_vel_time_
private

Definition at line 75 of file create_driver.h.

double CreateDriver::latch_duration_
private

Definition at line 87 of file create_driver.h.

double CreateDriver::loop_hz_
private

Definition at line 88 of file create_driver.h.

ros::Publisher CreateDriver::min_btn_pub_
protected

Definition at line 138 of file create_driver.h.

ca_msgs::Mode CreateDriver::mode_msg_
private

Definition at line 70 of file create_driver.h.

ros::Publisher CreateDriver::mode_pub_
protected

Definition at line 149 of file create_driver.h.

create::RobotModel CreateDriver::model_
private

Definition at line 67 of file create_driver.h.

ros::NodeHandle CreateDriver::nh_
protected

Definition at line 120 of file create_driver.h.

std::string CreateDriver::odom_frame_
private

Definition at line 86 of file create_driver.h.

nav_msgs::Odometry CreateDriver::odom_msg_
private

Definition at line 73 of file create_driver.h.

ros::Publisher CreateDriver::odom_pub_
protected

Definition at line 134 of file create_driver.h.

ros::Publisher CreateDriver::omni_char_pub_
protected

Definition at line 148 of file create_driver.h.

ros::Subscriber CreateDriver::play_song_sub_
protected

Definition at line 132 of file create_driver.h.

ros::Subscriber CreateDriver::power_led_sub_
protected

Definition at line 127 of file create_driver.h.

ros::NodeHandle CreateDriver::priv_nh_
protected

Definition at line 121 of file create_driver.h.

bool CreateDriver::publish_tf_
private

Definition at line 89 of file create_driver.h.

create::Create* CreateDriver::robot_
private

Definition at line 66 of file create_driver.h.

ros::Subscriber CreateDriver::set_ascii_sub_
protected

Definition at line 128 of file create_driver.h.

ros::Publisher CreateDriver::spot_btn_pub_
protected

Definition at line 140 of file create_driver.h.

ros::Subscriber CreateDriver::spot_led_sub_
protected

Definition at line 124 of file create_driver.h.

ros::Publisher CreateDriver::temperature_pub_
protected

Definition at line 146 of file create_driver.h.

tf::TransformBroadcaster CreateDriver::tf_broadcaster_
private

Definition at line 68 of file create_driver.h.

geometry_msgs::TransformStamped CreateDriver::tf_odom_
private

Definition at line 74 of file create_driver.h.

std_msgs::UInt16 CreateDriver::uint16_msg_
private

Definition at line 78 of file create_driver.h.

ros::Subscriber CreateDriver::undock_sub_
protected

Definition at line 130 of file create_driver.h.

ros::Publisher CreateDriver::voltage_pub_
protected

Definition at line 141 of file create_driver.h.

ros::Publisher CreateDriver::wheel_joint_pub_
protected

Definition at line 152 of file create_driver.h.

ros::Publisher CreateDriver::wheeldrop_pub_
protected

Definition at line 151 of file create_driver.h.


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


ca_driver
Author(s): Jacob Perron
autogenerated on Fri Jun 7 2019 21:45:23