shadowrobot::VirtualArm Class Reference

#include <virtual_arm.h>

Inheritance diagram for shadowrobot::VirtualArm:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual JointsMap getAllJointsData ()
virtual void getConfig (std::string joint_name)
virtual JointControllerData getContrl (std::string ctrlr_name)
virtual std::vector
< DiagnosticData
getDiagnostics ()
virtual JointData getJointData (std::string joint_name)
virtual short sendupdate (std::string joint_name, double target)
virtual short setConfig (std::vector< std::string > myConfig)
virtual short setContrl (std::string contrlr_name, JointControllerData ctrlr_data)
 VirtualArm ()
 ~VirtualArm ()
 destructor

Protected Member Functions

void initializeMap ()
double toDegrees (double rad)
double toRad (double deg)

Detailed Description

Definition at line 34 of file virtual_arm.h.


Constructor & Destructor Documentation

shadowrobot::VirtualArm::VirtualArm (  ) 

Initializes the necessary mappings with a static list of names.

Definition at line 28 of file virtual_arm.cpp.

shadowrobot::VirtualArm::~VirtualArm (  ) 

destructor

Definition at line 50 of file virtual_arm.cpp.


Member Function Documentation

SRArticulatedRobot::JointsMap shadowrobot::VirtualArm::getAllJointsData (  )  [virtual]

Get the data for all the joints.

Returns:
a mapping between the joints names and the information for each joint.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 170 of file virtual_arm.cpp.

void shadowrobot::VirtualArm::getConfig ( std::string  joint_name  )  [virtual]

Get the config of the palm

Todo:
Not implemented yet
Parameters:
joint_name 

Implements shadowrobot::SRArticulatedRobot.

Definition at line 211 of file virtual_arm.cpp.

JointControllerData shadowrobot::VirtualArm::getContrl ( std::string  contrlr_name  )  [virtual]

Get the controller parameters for a given controller name.

Parameters:
contrlr_name the name of the controller.
Returns:
The parameters of this controller

Implements shadowrobot::SRArticulatedRobot.

Definition at line 198 of file virtual_arm.cpp.

std::vector< DiagnosticData > shadowrobot::VirtualArm::getDiagnostics (  )  [virtual]

Generates a set of random data to be published by the diagnostic publisher, but keep the position and target as they are ( those are updated by the sendupdate() function).

Returns:
A vector containing all the diagnostics for the hand (motor information, etc...)

Implements shadowrobot::SRArticulatedRobot.

Definition at line 216 of file virtual_arm.cpp.

JointData shadowrobot::VirtualArm::getJointData ( std::string  joint_name  )  [virtual]

In the virtual arm, getJointData() simply fetches the data from a given joint in the joints_map. As the targets and positions are up to date, there's no need of reading other values here for those two values. However, we generate random values for the other data (temperature, current, etc...)

Parameters:
joint_name The name of the joint, as specified in joints_map.
Returns:
The information regarding this joint.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 146 of file virtual_arm.cpp.

void shadowrobot::VirtualArm::initializeMap (  )  [protected]

Initialise a mapping for the joints.

Definition at line 54 of file virtual_arm.cpp.

short shadowrobot::VirtualArm::sendupdate ( std::string  joint_name,
double  target 
) [virtual]

This function will set the target of the object to the given angle. It will also set the position to this target.

Todo:
This could be improved by implementing a control algorithm in this theoretic arm.
Parameters:
joint_name The Joint in joints_map you wish to send the target to.
target The target in degree
Returns:
0 if success ; -1 if error

Implements shadowrobot::SRArticulatedRobot.

Definition at line 105 of file virtual_arm.cpp.

short shadowrobot::VirtualArm::setConfig ( std::vector< std::string >  myConfig  )  [virtual]

Set the config of the palm

Todo:
Not implemented yet
Parameters:
myConfig 
Returns:

Implements shadowrobot::SRArticulatedRobot.

Definition at line 205 of file virtual_arm.cpp.

short shadowrobot::VirtualArm::setContrl ( std::string  contrlr_name,
JointControllerData  ctrlr_data 
) [virtual]

Set the controller parameters for a given controller name.

Parameters:
contrlr_name The name of the controller to setup.
ctrlr_data The data to pass to this controller.
Returns:
0 if success.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 192 of file virtual_arm.cpp.

double shadowrobot::VirtualArm::toDegrees ( double  rad  )  [inline, protected]

Convert an angle in radian to an angle in degrees.

Parameters:
deg the angle in rads
Returns:
the value in degrees.

Definition at line 110 of file virtual_arm.h.

double shadowrobot::VirtualArm::toRad ( double  deg  )  [inline, protected]

Convert an angle in degree to an angle in radians.

Parameters:
deg the angle in degrees
Returns:
the value in rads.

Definition at line 100 of file virtual_arm.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator


sr_hand
Author(s): Ugo Cupcic / ugo@shadowrobot.com, contact@shadowrobot.com
autogenerated on Fri Jan 11 09:32:58 2013