Public Member Functions | Private Member Functions | Private Attributes
robot Class Reference

Main robot control object. More...

#include <robot.h>

List of all members.

Public Member Functions

void checkTF ()
void reset_left ()
void reset_right ()
 robot ()

Private Member Functions

void move_arm_to_pose (float x, float y, float z, std::string frame, std::string group)

Private Attributes

float last_x
float last_y
float last_z
actionlib::SimpleActionClient
< arm_navigation_msgs::MoveArmAction
move_l_arm
actionlib::SimpleActionClient
< arm_navigation_msgs::MoveArmAction
move_r_arm
ros::NodeHandle node
ros::Time t
tf::TransformListener tfl

Detailed Description

Main robot control object.

The robot class controls the robot in response to the object recognition.

Definition at line 32 of file robot.h.


Constructor & Destructor Documentation

Creates a robot. This will listen to changes in the TF tree.

Definition at line 20 of file robot.cpp.


Member Function Documentation

void robot::checkTF ( )

Checks the TF tree for a new object position.

Definition at line 106 of file robot.cpp.

void robot::move_arm_to_pose ( float  x,
float  y,
float  z,
std::string  frame,
std::string  group 
) [private]

Move the given arm to the given pose based on the given reference frame.

Parameters:
xthe X position in meters
ythe Y position in meters
zthe Z position in meters
framethe reference to move the arm with respect to
groupthe group name for the arm joints

Definition at line 48 of file robot.cpp.

Reset the left arm to its start position.

Definition at line 42 of file robot.cpp.

Reset the right arm to its start position.

Definition at line 36 of file robot.cpp.


Member Data Documentation

float robot::last_x [private]

Definition at line 74 of file robot.h.

float robot::last_y [private]

Definition at line 74 of file robot.h.

float robot::last_z [private]

last known location of the object

Definition at line 74 of file robot.h.

Definition at line 72 of file robot.h.

used to move the robot's arms

Definition at line 72 of file robot.h.

main ROS node handle

Definition at line 67 of file robot.h.

ros::Time robot::t [private]

used to keep track of the last TF seen

Definition at line 69 of file robot.h.

used to keep track of the object in 3D space

Definition at line 71 of file robot.h.


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


rail_cv_project
Author(s): Russell Toris, David Kent, Adrian‎ Boteanu
autogenerated on Sat Dec 28 2013 17:31:25