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

Node for controlling the ARM. More...

#include <arm_control.h>

List of all members.

Public Member Functions

 ArmControl ()
 Calls the init and run methods.

Private Member Functions

void cartesianMovesCallback (const arm::cartesian_moves::ConstPtr &cmd)
 Callback for cartesian movement messages.
void constantMoveCallback (const arm::constant_move::ConstPtr &cmd)
 Callback for constant movement messages.
void constantMoveTimeCallback (const arm::constant_move_time::ConstPtr &cmd)
 Callback for constant movement by time messages.
void init ()
 Initializes the node.
void run ()
 Runs the node in a loop until a shutdown message is received.

Private Attributes

ManusArmarm_
CartesianMove cartesian_move_
ros::Subscriber cartesian_sub_
ConstantMove constant_move_
ros::Subscriber constant_sub_
ros::Subscriber constant_time_sub_
ros::NodeHandle n_
bool shutdown_
ros::ServiceClient time_client_

Detailed Description

Node for controlling the ARM.

This node receives movement commands from teleop nodes and moves the arm hardware appropriately. 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 30 of file arm_control.h.


Constructor & Destructor Documentation

Calls the init and run methods.

Definition at line 14 of file arm_control.cpp.


Member Function Documentation

void ArmControl::cartesianMovesCallback ( const arm::cartesian_moves::ConstPtr &  cmd) [private]

Callback for cartesian movement messages.

This method is called automatically when the node receives a cartesian movement message. The received message contains an array of cartesian moves and an ending time. The time server is polled to compare actual time to the ending time, and the arm will be moved, in sequence, according to the array of moves while time is remaining. If there is no time remaining, further moves are not executed and the callback exits.

Parameters:
cmdthe received message

Definition at line 113 of file arm_control.cpp.

void ArmControl::constantMoveCallback ( const arm::constant_move::ConstPtr &  cmd) [private]

Callback for constant movement messages.

This method is called automatically when the node receives a constant movement message. This message usually used for direct user control, such as operation with a keyboard. The received message contains position and speed data, and the callback will move the arm appropriately. The message also contains a query flag (the method will print movement data to the screen) and a quit flag (the method set the shutdown flag to true, causing the node to shutdown).

Parameters:
cmdthe received message

Definition at line 168 of file arm_control.cpp.

void ArmControl::constantMoveTimeCallback ( const arm::constant_move_time::ConstPtr &  cmd) [private]

Callback for constant movement by time messages.

This method is called automatically when the node receives a cartesian movement by time message. This method is similar in operation to the cartesian movement callback, instead using constant movements.

Parameters:
cmdthe received message

Definition at line 197 of file arm_control.cpp.

void ArmControl::init ( ) [private]

Initializes the node.

There are two functions of the init method: it first subscribes to the necessary ROS topics to receive movement commands, and it then initializes the arm hardware.

Definition at line 27 of file arm_control.cpp.

void ArmControl::run ( ) [private]

Runs the node in a loop until a shutdown message is received.

Before the main loop, the arm is moved into its origin position. The method then enters a spin loop until the shutdown flag is set to true (via a ROS message) or Ctrl+C is pressed. After the loop exits, the arm is moved into its final position.

Definition at line 63 of file arm_control.cpp.


Member Data Documentation

Definition at line 47 of file arm_control.h.

Definition at line 48 of file arm_control.h.

ros::Subscriber ArmControl::cartesian_sub_ [private]

Definition at line 43 of file arm_control.h.

Definition at line 49 of file arm_control.h.

ros::Subscriber ArmControl::constant_sub_ [private]

Definition at line 44 of file arm_control.h.

ros::Subscriber ArmControl::constant_time_sub_ [private]

Definition at line 45 of file arm_control.h.

ros::NodeHandle ArmControl::n_ [private]

Definition at line 42 of file arm_control.h.

bool ArmControl::shutdown_ [private]

Definition at line 50 of file arm_control.h.

ros::ServiceClient ArmControl::time_client_ [private]

Definition at line 46 of file arm_control.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