#include <kobuki_ros.hpp>
Public Member Functions | |
bool | init (ros::NodeHandle &nh, ros::NodeHandle &nh_pub) |
KobukiRos (std::string &node_name) | |
Default constructor. More... | |
bool | update () |
~KobukiRos () | |
Private Member Functions | |
void | advertiseTopics (ros::NodeHandle &nh) |
void | processStreamData () |
void | publishBumperEvent (const BumperEvent &event) |
void | publishButtonEvent (const ButtonEvent &event) |
void | publishCliffEvent (const CliffEvent &event) |
void | publishControllerInfo () |
void | publishDockIRData () |
void | publishInertia () |
void | publishInputEvent (const InputEvent &event) |
void | publishPowerEvent (const PowerEvent &event) |
void | publishRawControlCommand (const std::vector< short > &velocity_commands) |
void | publishRawDataCommand (Command::Buffer &buffer) |
Prints the raw data stream to a publisher. More... | |
void | publishRawDataStream (PacketFinder::BufferType &buffer) |
Prints the raw data stream to a publisher. More... | |
void | publishRawInertia () |
void | publishRobotEvent (const RobotEvent &event) |
void | publishSensorState () |
void | publishVersionInfo (const VersionInfo &version_info) |
Publish fw, hw, sw version information. More... | |
void | publishWheelEvent (const WheelEvent &event) |
void | publishWheelState () |
void | rosDebug (const std::string &msg) |
void | rosError (const std::string &msg) |
void | rosInfo (const std::string &msg) |
void | rosNamed (const std::vector< std::string > &msgs) |
void | rosWarn (const std::string &msg) |
void | subscribeControllerInfoCommand (const kobuki_msgs::ControllerInfoConstPtr msg) |
void | subscribeDigitalOutputCommand (const kobuki_msgs::DigitalOutputConstPtr) |
void | subscribeExternalPowerCommand (const kobuki_msgs::ExternalPowerConstPtr) |
void | subscribeLed1Command (const kobuki_msgs::LedConstPtr) |
void | subscribeLed2Command (const kobuki_msgs::LedConstPtr) |
void | subscribeMotorPower (const kobuki_msgs::MotorPowerConstPtr msg) |
void | subscribeResetOdometry (const std_msgs::EmptyConstPtr) |
Reset the odometry variables. More... | |
void | subscribeSoundCommand (const kobuki_msgs::SoundConstPtr) |
Play a predefined sound (single sound or sound sequence) More... | |
void | subscribeTopics (ros::NodeHandle &nh) |
void | subscribeVelocityCommand (const geometry_msgs::TwistConstPtr) |
Definition at line 84 of file kobuki_ros.hpp.
kobuki::KobukiRos::KobukiRos | ( | std::string & | node_name | ) |
Default constructor.
Make sure you call the init() method to fully define this node.
Definition at line 61 of file kobuki_ros.cpp.
kobuki::KobukiRos::~KobukiRos | ( | ) |
This will wait some time while kobuki internally closes its threads and destructs itself.
Definition at line 99 of file kobuki_ros.cpp.
|
private |
Two groups of publishers, one required by turtlebot, the other for kobuki esoterics.
Definition at line 303 of file kobuki_ros.cpp.
bool kobuki::KobukiRos::init | ( | ros::NodeHandle & | nh, |
ros::NodeHandle & | nh_pub | ||
) |
Definition at line 104 of file kobuki_ros.cpp.
|
private |
Definition at line 49 of file slot_callbacks.cpp.
|
private |
Definition at line 287 of file slot_callbacks.cpp.
|
private |
Definition at line 267 of file slot_callbacks.cpp.
|
private |
Definition at line 307 of file slot_callbacks.cpp.
|
private |
Definition at line 247 of file slot_callbacks.cpp.
|
private |
Definition at line 184 of file slot_callbacks.cpp.
|
private |
Definition at line 117 of file slot_callbacks.cpp.
|
private |
Definition at line 371 of file slot_callbacks.cpp.
|
private |
Definition at line 347 of file slot_callbacks.cpp.
|
private |
Definition at line 472 of file slot_callbacks.cpp.
|
private |
Prints the raw data stream to a publisher.
This is a lazy publisher, it only publishes if someone is listening. It publishes the hex byte values of the raw data commands. Useful for debugging command to protocol byte packets to the firmware.
The signal which calls this function is sending a copy of the buffer (don't worry about mutexes). Be ideal if we used const PacketFinder::BufferType here, but haven't updated PushPop to work with consts yet.
buffer |
Definition at line 410 of file slot_callbacks.cpp.
|
private |
Prints the raw data stream to a publisher.
This is a lazy publisher, it only publishes if someone is listening. It publishes the hex byte values of the raw data (incoming) stream. Useful for checking when bytes get mangled.
The signal which calls this function is sending a copy of the buffer (don't worry about mutexes). Be ideal if we used const PacketFinder::BufferType here, but haven't updated PushPop to work with consts yet.
buffer |
Definition at line 437 of file slot_callbacks.cpp.
|
private |
Definition at line 152 of file slot_callbacks.cpp.
|
private |
Definition at line 382 of file slot_callbacks.cpp.
|
private |
Definition at line 61 of file slot_callbacks.cpp.
|
private |
Publish fw, hw, sw version information.
The driver will only gather this data when initialising so it is important that this publisher is latched.
Definition at line 216 of file slot_callbacks.cpp.
|
private |
Definition at line 328 of file slot_callbacks.cpp.
|
private |
Definition at line 98 of file slot_callbacks.cpp.
|
inlineprivate |
Definition at line 174 of file kobuki_ros.hpp.
|
inlineprivate |
Definition at line 177 of file kobuki_ros.hpp.
|
inlineprivate |
Definition at line 175 of file kobuki_ros.hpp.
|
inlineprivate |
Definition at line 178 of file kobuki_ros.hpp.
|
inlineprivate |
Definition at line 176 of file kobuki_ros.hpp.
|
private |
Definition at line 228 of file subscriber_callbacks.cpp.
|
private |
Definition at line 93 of file subscriber_callbacks.cpp.
|
private |
Definition at line 104 of file subscriber_callbacks.cpp.
|
private |
Definition at line 69 of file subscriber_callbacks.cpp.
|
private |
Definition at line 81 of file subscriber_callbacks.cpp.
|
private |
Definition at line 207 of file subscriber_callbacks.cpp.
|
private |
Reset the odometry variables.
Definition at line 195 of file subscriber_callbacks.cpp.
|
private |
Play a predefined sound (single sound or sound sequence)
Definition at line 155 of file subscriber_callbacks.cpp.
|
private |
Two groups of subscribers, one required by turtlebot, the other for kobuki esoterics.
Definition at line 335 of file kobuki_ros.cpp.
|
private |
Definition at line 53 of file subscriber_callbacks.cpp.
bool kobuki::KobukiRos::update | ( | ) |
This is a worker function that runs in a background thread initiated by the nodelet. It gathers diagnostics information from the kobuki driver, and broadcasts the results to the rest of the ros ecosystem.
Note that the actual driver data is collected via the slot callbacks in this class.
Definition at line 248 of file kobuki_ros.cpp.
|
private |
Definition at line 214 of file kobuki_ros.hpp.
|
private |
Definition at line 205 of file kobuki_ros.hpp.
|
private |
Definition at line 208 of file kobuki_ros.hpp.
|
private |
Definition at line 110 of file kobuki_ros.hpp.
|
private |
Definition at line 109 of file kobuki_ros.hpp.
|
private |
Definition at line 207 of file kobuki_ros.hpp.
|
private |
Definition at line 110 of file kobuki_ros.hpp.
|
private |
Definition at line 101 of file kobuki_ros.hpp.
|
private |
Definition at line 114 of file kobuki_ros.hpp.
|
private |
Definition at line 107 of file kobuki_ros.hpp.
|
private |
Definition at line 113 of file kobuki_ros.hpp.
|
private |
Definition at line 213 of file kobuki_ros.hpp.
|
private |
Definition at line 108 of file kobuki_ros.hpp.
|
private |
Definition at line 113 of file kobuki_ros.hpp.
|
private |
Definition at line 212 of file kobuki_ros.hpp.
|
private |
Definition at line 108 of file kobuki_ros.hpp.
|
private |
Definition at line 109 of file kobuki_ros.hpp.
|
private |
Definition at line 108 of file kobuki_ros.hpp.
|
private |
Definition at line 99 of file kobuki_ros.hpp.
|
private |
Definition at line 98 of file kobuki_ros.hpp.
|
private |
Definition at line 115 of file kobuki_ros.hpp.
|
private |
Definition at line 115 of file kobuki_ros.hpp.
|
private |
Definition at line 210 of file kobuki_ros.hpp.
|
private |
Definition at line 116 of file kobuki_ros.hpp.
|
private |
Definition at line 97 of file kobuki_ros.hpp.
|
private |
Definition at line 100 of file kobuki_ros.hpp.
|
private |
Definition at line 110 of file kobuki_ros.hpp.
|
private |
Definition at line 111 of file kobuki_ros.hpp.
|
private |
Definition at line 111 of file kobuki_ros.hpp.
|
private |
Definition at line 111 of file kobuki_ros.hpp.
|
private |
Definition at line 108 of file kobuki_ros.hpp.
|
private |
Definition at line 116 of file kobuki_ros.hpp.
|
private |
Definition at line 109 of file kobuki_ros.hpp.
|
private |
Definition at line 108 of file kobuki_ros.hpp.
|
private |
Definition at line 102 of file kobuki_ros.hpp.
|
private |
Definition at line 141 of file kobuki_ros.hpp.
|
private |
Definition at line 140 of file kobuki_ros.hpp.
|
private |
Definition at line 142 of file kobuki_ros.hpp.
|
private |
Definition at line 139 of file kobuki_ros.hpp.
|
private |
Definition at line 147 of file kobuki_ros.hpp.
|
private |
Definition at line 147 of file kobuki_ros.hpp.
|
private |
Definition at line 147 of file kobuki_ros.hpp.
|
private |
Definition at line 145 of file kobuki_ros.hpp.
|
private |
Definition at line 148 of file kobuki_ros.hpp.
|
private |
Definition at line 144 of file kobuki_ros.hpp.
|
private |
Definition at line 151 of file kobuki_ros.hpp.
|
private |
Definition at line 149 of file kobuki_ros.hpp.
|
private |
Definition at line 150 of file kobuki_ros.hpp.
|
private |
Definition at line 146 of file kobuki_ros.hpp.
|
private |
Definition at line 138 of file kobuki_ros.hpp.
|
private |
Definition at line 137 of file kobuki_ros.hpp.
|
private |
Definition at line 147 of file kobuki_ros.hpp.
|
private |
Definition at line 143 of file kobuki_ros.hpp.
|
private |
Definition at line 115 of file kobuki_ros.hpp.
|
private |
Definition at line 211 of file kobuki_ros.hpp.
|
private |
Definition at line 204 of file kobuki_ros.hpp.
|
private |
Definition at line 113 of file kobuki_ros.hpp.
|
private |
Definition at line 107 of file kobuki_ros.hpp.
|
private |
Definition at line 206 of file kobuki_ros.hpp.
|
private |
Definition at line 209 of file kobuki_ros.hpp.
|
private |
Definition at line 110 of file kobuki_ros.hpp.