$search

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:
ns The 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.

EECartImpedArm::~EECartImpedArm (  ) 

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:
goal The trajectory to which to add this point (at the end)
x Position in x of this point
y Position in y of this point
z Position in z of this point
ox First (x) value of the quaternion giving the Cartesian orientation at this point
oy Second (y) value of the quaternion giving the Cartesian orientation at this point
oz Third (z) value of the quaternion giving the Cartesian orientation at this point
ow Fourth (w) value of the quaternion giving the Cartesian orientation at this point
fx The force or stiffness in the x direction at this point
fy The force or stiffness in the y direction at this point
fz The force or stiffness in the z direction at this point
tx The torque or rotational stiffness around the x axis at this point
ty The torque or rotational stiffness around the y axis at this point
tz The torque or rotational stiffness around the z axis at this point
iswfx True if there is a force in the x direction, false if there is a stiffness
iswfy True if there is a force in the y direction, false if there is a stiffness
iswfz True if there is a force in the z direction, false if there is a stiffness
iswtx True if there is a torque around the x axis, false if there is a stiffness
iswty True if there is a torque around the y axis, false if there is a stiffness
iswtz True if there is a torque around the z axis, false if there is a stiffness
ts The 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_id The 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.

void EECartImpedArm::startTrajectory ( ee_cart_imped_msgs::EECartImpedGoal  goal,
bool  wait = true 
)

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:
goal The trajectory to execute
wait If 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.

void EECartImpedArm::stopTrajectory (  ) 

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:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


ee_cart_imped_action
Author(s): Jenny Barry, Mario Bollini, and Huan Liu
autogenerated on Sun Mar 3 11:46:34 2013