Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes
CreateDriver Class Reference

#include <create_driver.h>

List of all members.

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::Create * robot_
tf::TransformBroadcaster tf_broadcaster_
geometry_msgs::TransformStamped tf_odom_
std_msgs::UInt16 uint16_msg_

Detailed Description

Definition at line 33 of file create_driver.h.


Constructor & Destructor Documentation

Definition at line 4 of file create_driver.cpp.

Definition at line 128 of file create_driver.cpp.


Member Function Documentation

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

Definition at line 156 of file create_driver.cpp.

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

Definition at line 135 of file create_driver.cpp.

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

Definition at line 141 of file create_driver.cpp.

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

Definition at line 227 of file create_driver.cpp.

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

Definition at line 210 of file create_driver.cpp.

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

Definition at line 151 of file create_driver.cpp.

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

Definition at line 235 of file create_driver.cpp.

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

Definition at line 161 of file create_driver.cpp.

Definition at line 457 of file create_driver.cpp.

void CreateDriver::publishBumperInfo ( ) [private]

Definition at line 563 of file create_driver.cpp.

void CreateDriver::publishButtonPresses ( ) const [private]

Definition at line 502 of file create_driver.cpp.

void CreateDriver::publishJointState ( ) [private]

Definition at line 445 of file create_driver.cpp.

void CreateDriver::publishMode ( ) [private]

Definition at line 538 of file create_driver.cpp.

void CreateDriver::publishOdom ( ) [private]

Definition at line 396 of file create_driver.cpp.

void CreateDriver::publishOmniChar ( ) [private]

Definition at line 530 of file create_driver.cpp.

void CreateDriver::publishWheeldrop ( ) [private]

Definition at line 589 of file create_driver.cpp.

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

Definition at line 180 of file create_driver.cpp.

void CreateDriver::spin ( ) [virtual]

Definition at line 602 of file create_driver.cpp.

void CreateDriver::spinOnce ( ) [virtual]

Definition at line 595 of file create_driver.cpp.

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

Definition at line 146 of file create_driver.cpp.

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

Definition at line 221 of file create_driver.cpp.

bool CreateDriver::update ( ) [private]

Definition at line 243 of file create_driver.cpp.

Definition at line 263 of file create_driver.cpp.

Definition at line 384 of file create_driver.cpp.

Definition at line 361 of file create_driver.cpp.

Definition at line 316 of file create_driver.cpp.

Definition at line 337 of file create_driver.cpp.


Member Data Documentation

std::string CreateDriver::base_frame_ [private]

Definition at line 55 of file create_driver.h.

int CreateDriver::baud_ [private]

Definition at line 60 of file create_driver.h.

ca_msgs::Bumper CreateDriver::bumper_msg_ [private]

Definition at line 42 of file create_driver.h.

Definition at line 120 of file create_driver.h.

Definition at line 115 of file create_driver.h.

Definition at line 113 of file create_driver.h.

Definition at line 114 of file create_driver.h.

ca_msgs::ChargingState CreateDriver::charging_state_msg_ [private]

Definition at line 41 of file create_driver.h.

Definition at line 117 of file create_driver.h.

Definition at line 96 of file create_driver.h.

Definition at line 105 of file create_driver.h.

Definition at line 92 of file create_driver.h.

Definition at line 112 of file create_driver.h.

Definition at line 106 of file create_driver.h.

Definition at line 93 of file create_driver.h.

Definition at line 101 of file create_driver.h.

std::string CreateDriver::dev_ [private]

Definition at line 54 of file create_driver.h.

Definition at line 39 of file create_driver.h.

Definition at line 109 of file create_driver.h.

Definition at line 95 of file create_driver.h.

Definition at line 99 of file create_driver.h.

std_msgs::Empty CreateDriver::empty_msg_ [private]

Definition at line 46 of file create_driver.h.

std_msgs::Float32 CreateDriver::float32_msg_ [private]

Definition at line 47 of file create_driver.h.

Definition at line 107 of file create_driver.h.

std_msgs::Int16 CreateDriver::int16_msg_ [private]

Definition at line 49 of file create_driver.h.

Definition at line 51 of file create_driver.h.

sensor_msgs::JointState CreateDriver::joint_state_msg_ [private]

Definition at line 50 of file create_driver.h.

Definition at line 45 of file create_driver.h.

Definition at line 57 of file create_driver.h.

double CreateDriver::loop_hz_ [private]

Definition at line 58 of file create_driver.h.

Definition at line 108 of file create_driver.h.

ca_msgs::Mode CreateDriver::mode_msg_ [private]

Definition at line 40 of file create_driver.h.

Definition at line 119 of file create_driver.h.

create::RobotModel CreateDriver::model_ [private]

Definition at line 37 of file create_driver.h.

Definition at line 90 of file create_driver.h.

std::string CreateDriver::odom_frame_ [private]

Definition at line 56 of file create_driver.h.

nav_msgs::Odometry CreateDriver::odom_msg_ [private]

Definition at line 43 of file create_driver.h.

Definition at line 104 of file create_driver.h.

Definition at line 118 of file create_driver.h.

Definition at line 102 of file create_driver.h.

Definition at line 97 of file create_driver.h.

Definition at line 91 of file create_driver.h.

bool CreateDriver::publish_tf_ [private]

Definition at line 59 of file create_driver.h.

create::Create* CreateDriver::robot_ [private]

Definition at line 36 of file create_driver.h.

Definition at line 98 of file create_driver.h.

Definition at line 110 of file create_driver.h.

Definition at line 94 of file create_driver.h.

Definition at line 116 of file create_driver.h.

Definition at line 38 of file create_driver.h.

geometry_msgs::TransformStamped CreateDriver::tf_odom_ [private]

Definition at line 44 of file create_driver.h.

std_msgs::UInt16 CreateDriver::uint16_msg_ [private]

Definition at line 48 of file create_driver.h.

Definition at line 100 of file create_driver.h.

Definition at line 111 of file create_driver.h.

Definition at line 122 of file create_driver.h.

Definition at line 121 of file create_driver.h.


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


ca_driver
Author(s): Jacob Perron
autogenerated on Thu Apr 20 2017 02:24:49