Public Member Functions | Protected Member Functions | List of all members
shadowrobot::VirtualArm Class Reference

#include <virtual_arm.h>

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

Public Member Functions

virtual JointsMap getAllJointsData ()
 
virtual void getConfig (std::string joint_name)
 
virtual JointControllerData getContrl (std::string ctrlr_name)
 
virtual std::vector< DiagnosticDatagetDiagnostics ()
 
virtual JointData getJointData (std::string joint_name)
 
virtual int16_t sendupdate (std::string joint_name, double target)
 
virtual int16_t setConfig (std::vector< std::string > myConfig)
 
virtual int16_t setContrl (std::string contrlr_name, JointControllerData ctrlr_data)
 
 VirtualArm ()
 
virtual ~VirtualArm ()
 
- Public Member Functions inherited from shadowrobot::SRArticulatedRobot
 SRArticulatedRobot ()
 
virtual ~SRArticulatedRobot ()
 

Protected Member Functions

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

Additional Inherited Members

- Public Types inherited from shadowrobot::SRArticulatedRobot
typedef std::map< std::string, JointDataJointsMap
 
typedef std::map< std::string, enum controller_parametersParametersMap
 
- Public Attributes inherited from shadowrobot::SRArticulatedRobot
boost::mutex controllers_map_mutex
 
JointsMap joints_map
 A mapping between the joint names and the information regarding those joints. More...
 
boost::mutex joints_map_mutex
 
ParametersMap parameters_map
 A mapping between the parameter names and their values. More...
 
boost::mutex parameters_map_mutex
 
- Protected Attributes inherited from shadowrobot::SRArticulatedRobot
boost::shared_ptr< self_test::TestRunnerself_test
 this is the handle for the self tests. More...
 

Detailed Description

Definition at line 35 of file virtual_arm.h.

Constructor & Destructor Documentation

shadowrobot::VirtualArm::VirtualArm ( )

Initializes the necessary mappings with a static list of names.

Definition at line 42 of file virtual_arm.cpp.

shadowrobot::VirtualArm::~VirtualArm ( )
virtual

Definition at line 64 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 227 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 270 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_namethe name of the controller.
Returns
The parameters of this controller

Implements shadowrobot::SRArticulatedRobot.

Definition at line 257 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 275 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_nameThe name of the joint, as specified in joints_map.
Returns
The information regarding this joint.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 201 of file virtual_arm.cpp.

void shadowrobot::VirtualArm::initializeMap ( )
protected

Initialise a mapping for the joints.

Definition at line 68 of file virtual_arm.cpp.

int16_t 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_nameThe Joint in joints_map you wish to send the target to.
targetThe target in degree
Returns
0 if success ; -1 if error

Implements shadowrobot::SRArticulatedRobot.

Definition at line 157 of file virtual_arm.cpp.

int16_t 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 264 of file virtual_arm.cpp.

int16_t shadowrobot::VirtualArm::setContrl ( std::string  contrlr_name,
JointControllerData  ctrlr_data 
)
virtual

Set the controller parameters for a given controller name.

Parameters
contrlr_nameThe name of the controller to setup.
ctrlr_dataThe data to pass to this controller.
Returns
0 if success.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 251 of file virtual_arm.cpp.

double shadowrobot::VirtualArm::toDegrees ( double  rad)
inlineprotected

Convert an angle in radian to an angle in degrees.

Parameters
radthe angle in rads
Returns
the value in degrees.

Definition at line 117 of file virtual_arm.h.

double shadowrobot::VirtualArm::toRad ( double  deg)
inlineprotected

Convert an angle in degree to an angle in radians.

Parameters
degthe angle in degrees
Returns
the value in rads.

Definition at line 107 of file virtual_arm.h.


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


sr_hand
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:53