Provides direct communication to the Rovio to control the motors. More...
#include <rovio_move.h>
Public Member Functions | |
move_controller () | |
Creates a move_controller using ROS parameters. | |
void | update () |
Sends commands to the Rovio to change the wheel speeds. head sensor information. | |
~move_controller () | |
Cleans up any resources and connections to the Rovio. | |
Private Member Functions | |
void | cmd_vel_callback (const geometry_msgs::Twist::ConstPtr &msg) |
cmd_vel topic callback function. | |
void | man_drv_callback (const rovio_shared::man_drv::ConstPtr &msg) |
man_drv topic callback function. | |
Private Attributes | |
ros::Subscriber | cmd_vel |
int | drive |
std::string | host |
ros::Subscriber | man_drv |
ros::NodeHandle | node |
int | rotate |
rovio_http * | rovio |
int | speed |
Provides direct communication to the Rovio to control the motors.
The move_controller handles communication to the Rovio's motor devices. ROS nodes and topics are created and maintained within this object.
Definition at line 64 of file rovio_move.h.
Creates a move_controller using ROS parameters.
Creates a move_controller object that can be used control the Rovio's motors. A valid username, password, and host must be set as ROS parameters.
Definition at line 61 of file rovio_move.cpp.
Cleans up any resources and connections to the Rovio.
Uses the deconstructor from the rovio_http class to clean up any resources and connections to the Rovio.
Definition at line 97 of file rovio_move.cpp.
void move_controller::cmd_vel_callback | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) | [private] |
cmd_vel topic callback function.
Process the twist message and set the appropriate fields. This function is adapted from http://www.ros.org/wiki/rovio_controller. A positive angular-z value corresponds to a clockwise rotation. Movement along linear-y corresponds to moving left/right and movement along linear-x corresponds to moving forwards/backwards.
msg | the message for the man_drv topic |
Definition at line 154 of file rovio_move.cpp.
void move_controller::man_drv_callback | ( | const rovio_shared::man_drv::ConstPtr & | msg | ) | [private] |
man_drv topic callback function.
Process the manual drive command and set the appropriate fields.
msg | the message for the man_drv topic |
Definition at line 133 of file rovio_move.cpp.
void move_controller::update | ( | ) |
Sends commands to the Rovio to change the wheel speeds. head sensor information.
Based on the most recent message received by either the man_drive or cmd_vel topic, one of Rovio's motor commands is sent to the robot.
Definition at line 103 of file rovio_move.cpp.
ros::Subscriber move_controller::cmd_vel [private] |
the man_drv and cmd_vel topics
Definition at line 112 of file rovio_move.h.
int move_controller::drive [private] |
Definition at line 114 of file rovio_move.h.
std::string move_controller::host [private] |
host of the Rovio
Definition at line 108 of file rovio_move.h.
ros::Subscriber move_controller::man_drv [private] |
Definition at line 112 of file rovio_move.h.
ros::NodeHandle move_controller::node [private] |
a handle for this ROS node
Definition at line 110 of file rovio_move.h.
int move_controller::rotate [private] |
used to move the Rovio in the update function
Definition at line 114 of file rovio_move.h.
rovio_http* move_controller::rovio [private] |
communicates with the Rovio
Definition at line 109 of file rovio_move.h.
int move_controller::speed [private] |
Definition at line 114 of file rovio_move.h.