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

Node for ARM teleop from the neuron dish. More...

#include <teleop_arm_dish.h>

List of all members.

Public Member Functions

 TeleopArmDish ()
 Calls the init and run methods.

Private Member Functions

void callback (const burst_calc::cat::ConstPtr &c)
 Callback for center of trajectory messages.
double getArmCoord (double coord)
 Converts CAT units to ARM units.
void getParams ()
 Gets the ROS server parameters necessary for proper operation.
void init ()
 Initializes the node.
void publishCartesianMove ()
 Publishes a cartesian movement command.
void publishConstantMove ()
 Publishes a constant movement command.
void run ()
 Runs the node in a loop until Ctrl+C is pressed.

Private Attributes

double arm_safe_range_
ros::Subscriber cat_sub_
ros::Publisher cmd_pub_
double max_range_from_midpoint_
ros::NodeHandle n_
std::queue< burst_calc::cat > queue_
int speed_
ros::ServiceClient time_client_

Detailed Description

Node for ARM teleop from the neuron dish.

This node receives CAT (center of activity trajectory) data from the CAT creator node and then creates and publishes movement commands. The operation of the node is autonomous; after the object has been created, the node will run with no further operation.

Author:
Jonathan Hasenzahl

Definition at line 25 of file teleop_arm_dish.h.


Constructor & Destructor Documentation

Calls the init and run methods.

Definition at line 20 of file teleop_arm_dish.cpp.


Member Function Documentation

void TeleopArmDish::callback ( const burst_calc::cat::ConstPtr &  c) [private]

Callback for center of trajectory messages.

This method is called automatically when the node receieves a center of activity trajectory message. It puts the message into the command queue.

Parameters:
cthe received message

Definition at line 108 of file teleop_arm_dish.cpp.

double TeleopArmDish::getArmCoord ( double  coord) [private]

Converts CAT units to ARM units.

CAT units range from 1 to 8 on each axis. ARM units are described in ManusArm.hpp and range from approximately -28,000 to 28,000 on each axis.

Parameters:
coordthe coordinate in CAT units
Returns:
the coordinate in ARM units

Definition at line 325 of file teleop_arm_dish.cpp.

void TeleopArmDish::getParams ( ) [private]

Gets the ROS server parameters necessary for proper operation.

Definition at line 56 of file teleop_arm_dish.cpp.

void TeleopArmDish::init ( ) [private]

Initializes the node.

This method first calls getParam to get ROS server parameters. It then starts the publisher and service client, and waits for a subscriber to its publisher before starting its own subscriber.

Definition at line 33 of file teleop_arm_dish.cpp.

Publishes a cartesian movement command.

This method retrieves a center of activity trajectory (CAT) message from the front of the command queue and creates and publishes a cartesian movement message derived from that CAT.

Definition at line 120 of file teleop_arm_dish.cpp.

Publishes a constant movement command.

This method retrieves a center of activity trajectory (CAT) message from the front of the command queue and creates and publishes a constant movement message derived from that CAT.

Definition at line 206 of file teleop_arm_dish.cpp.

void TeleopArmDish::run ( ) [private]

Runs the node in a loop until Ctrl+C is pressed.

In the loop, the node spins and publishes any commands that are waiting in the queue, using either publishCartesianMove or publishConstantMove.

Definition at line 86 of file teleop_arm_dish.cpp.


Member Data Documentation

Definition at line 47 of file teleop_arm_dish.h.

ros::Subscriber TeleopArmDish::cat_sub_ [private]

Definition at line 40 of file teleop_arm_dish.h.

ros::Publisher TeleopArmDish::cmd_pub_ [private]

Definition at line 41 of file teleop_arm_dish.h.

Definition at line 48 of file teleop_arm_dish.h.

ros::NodeHandle TeleopArmDish::n_ [private]

Definition at line 39 of file teleop_arm_dish.h.

std::queue<burst_calc::cat> TeleopArmDish::queue_ [private]

Definition at line 44 of file teleop_arm_dish.h.

int TeleopArmDish::speed_ [private]

Definition at line 46 of file teleop_arm_dish.h.

ros::ServiceClient TeleopArmDish::time_client_ [private]

Definition at line 42 of file teleop_arm_dish.h.


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


arm
Author(s): Jonathan Hasenzahl
autogenerated on Sun Jan 5 2014 11:12:32