Public Member Functions | Static Public Member Functions | Private Attributes
EECartImpedArm Class Reference

A wrapper around the client class for the EECartImpedAction. More...

#include <ee_cart_imped_arm.hh>

List of all members.

Public Member Functions

 EECartImpedArm (std::string ns)
 Creates a new client and waits for the server to come up.
void startTrajectory (ee_cart_imped_msgs::EECartImpedGoal goal, bool wait=true)
 Sends a goal to the server.
void stopTrajectory ()
 Stops the arm.
 ~EECartImpedArm ()
 Deletes the client.

Static Public Member Functions

static void addTrajectoryPoint (ee_cart_imped_msgs::EECartImpedGoal &goal, double x, double y, double z, double ox, double oy, double oz, double ow, double fx, double fy, double fz, double tx, double ty, double tz, bool iswfx, bool iswfy, bool iswfz, bool iswtx, bool iswty, bool iswtz, double ts, std::string frame_id)
 Adds a trajectory point to the provided trajectory.

Private Attributes

EECartImpedClienttraj_client_
 The action client.

Detailed Description

A wrapper around the client class for the EECartImpedAction.

It is intended to make interacting with the action server simple for most tasks. It allows a user to start or stop a trajectory. It also includes a helper function for creating trajectories more easily.

Definition at line 27 of file ee_cart_imped_arm.hh.


Constructor & Destructor Documentation

EECartImpedArm::EECartImpedArm ( std::string  ns)

Creates a new client and waits for the server to come up.

Parameters:
nsThe namespace of the action server. Multiple action servers may be running (to, for example, control both arms) so it is necessary to specify for which server this client is being created. If you launch the controller and action with the provided launch files the two valid options for ns are "r_arm_cart_imped_controller" for the right arm and "l_arm_cart_imped_controller" for the left arm. In general, the valid choices are the namespaces of any EECartImpedAction nodes.

Definition at line 4 of file ee_cart_imped_arm.cpp.

Deletes the client.

Definition at line 11 of file ee_cart_imped_arm.cpp.


Member Function Documentation

void EECartImpedArm::addTrajectoryPoint ( ee_cart_imped_msgs::EECartImpedGoal goal,
double  x,
double  y,
double  z,
double  ox,
double  oy,
double  oz,
double  ow,
double  fx,
double  fy,
double  fz,
double  tx,
double  ty,
double  tz,
bool  iswfx,
bool  iswfy,
bool  iswfz,
bool  iswtx,
bool  iswty,
bool  iswtz,
double  ts,
std::string  frame_id 
) [static]

Adds a trajectory point to the provided trajectory.

This is a useful function when creating a trajectory. It takes all of the necessary numbers and turns them into one trajectory point, which it appends to the trajectory points already contained in goal.

Parameters:
goalThe trajectory to which to add this point (at the end)
xPosition in x of this point
yPosition in y of this point
zPosition in z of this point
oxFirst (x) value of the quaternion giving the Cartesian orientation at this point
oySecond (y) value of the quaternion giving the Cartesian orientation at this point
ozThird (z) value of the quaternion giving the Cartesian orientation at this point
owFourth (w) value of the quaternion giving the Cartesian orientation at this point
fxThe force or stiffness in the x direction at this point
fyThe force or stiffness in the y direction at this point
fzThe force or stiffness in the z direction at this point
txThe torque or rotational stiffness around the x axis at this point
tyThe torque or rotational stiffness around the y axis at this point
tzThe torque or rotational stiffness around the z axis at this point
iswfxTrue if there is a force in the x direction, false if there is a stiffness
iswfyTrue if there is a force in the y direction, false if there is a stiffness
iswfzTrue if there is a force in the z direction, false if there is a stiffness
iswtxTrue if there is a torque around the x axis, false if there is a stiffness
iswtyTrue if there is a torque around the y axis, false if there is a stiffness
iswtzTrue if there is a torque around the z axis, false if there is a stiffness
tsThe time in seconds after the START of the trajectory that this point should be achieved. Note that this the cummulative time, NOT the time achieving this point should take. This time should be larger than the time for the point before.
frame_idThe frame_id of this point. If left as an empty string, will be interpreted as the root_name frame of the controller (probably /torso_lift_link)
Returns:
By reference, a new trajectory point is added to goal

Definition at line 40 of file ee_cart_imped_arm.cpp.

Sends a goal to the server.

Blocks for 200s or until goal is aborted or finished. If the goal times out, it is cancelled. If the goal has been aborted (due to timeout or any other reason), a warning is printed. The arm that performs the trajectory was selected through the ns parameter provided to EECartImpedArm::EECartImpedArm().

Parameters:
goalThe trajectory to execute
waitIf set to false this function will return immediately upon sending the goal to the action server; otherwise it will wait for the completion of the goal.

Definition at line 15 of file ee_cart_imped_arm.cpp.

Stops the arm.

This sends the cancelAllGoals signal to the action server. This causes the arm to hold its last point. Note that "point" includes the force/stiffness. If the arm was exerting a specified force when stopTrajectory was called, it will continue to exert that force.

Definition at line 35 of file ee_cart_imped_arm.cpp.


Member Data Documentation

The action client.

Sends goals and cancel signals to the action server. See the actionlib documentation for more details.

Definition at line 38 of file ee_cart_imped_arm.hh.


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


ee_cart_imped_action
Author(s): Jenny Barry, Mario Bollini, and Huan Liu
autogenerated on Sun Jan 5 2014 11:14:46