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

#include <real_shadowhand.h>

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

Public Member Functions

virtual JointsMap getAllJointsData ()
 
virtual void getConfig (std::string joint_name)
 
virtual JointControllerData getContrl (std::string contrlr_name)
 
virtual std::vector< DiagnosticDatagetDiagnostics ()
 
virtual JointData getJointData (std::string joint_name)
 
 RealShadowhand ()
 
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)
 
virtual ~RealShadowhand ()
 
- Public Member Functions inherited from shadowrobot::SRArticulatedRobot
 SRArticulatedRobot ()
 
virtual ~SRArticulatedRobot ()
 

Protected Member Functions

void initializeMap ()
 
void posttest (diagnostic_updater::DiagnosticStatusWrapper &status)
 
void pretest (diagnostic_updater::DiagnosticStatusWrapper &status)
 
void test_messages (diagnostic_updater::DiagnosticStatusWrapper &status)
 
std::pair< unsigned char, std::stringtest_messages_routine (std::string joint_name, unsigned int repeat, ros::Rate rate)
 

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

The real shadowhand class is a class used to access the C code of the Dextrous Hand.

Definition at line 57 of file real_shadowhand.h.

Constructor & Destructor Documentation

shadowrobot::RealShadowhand::RealShadowhand ( )

Constructor for the real Shadowhand: initialize the connection to the robot and also initialize the joint_map containing the mapping between joint_names and their data.

Definition at line 48 of file real_shadowhand.cpp.

shadowrobot::RealShadowhand::~RealShadowhand ( )
virtual

Definition at line 74 of file real_shadowhand.cpp.

Member Function Documentation

SRArticulatedRobot::JointsMap shadowrobot::RealShadowhand::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 220 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::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 346 of file real_shadowhand.cpp.

JointControllerData shadowrobot::RealShadowhand::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 310 of file real_shadowhand.cpp.

std::vector< DiagnosticData > shadowrobot::RealShadowhand::getDiagnostics ( )
virtual

Get the diagnostics for the whole articulated robot.

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

Implements shadowrobot::SRArticulatedRobot.

Definition at line 351 of file real_shadowhand.cpp.

JointData shadowrobot::RealShadowhand::getJointData ( std::string  joint_name)
virtual

Get the joint data for a specific joint.

See also
JointData
Parameters
joint_nameThe name of the joint, as specified in joints_map.
Returns
The information regarding this joint.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 175 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::initializeMap ( )
protected

Definition at line 78 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::posttest ( diagnostic_updater::DiagnosticStatusWrapper status)
protected

A set of tasks to run after the tests:

  • release the mutexes
Parameters
statusthe status of the posttest

Definition at line 471 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::pretest ( diagnostic_updater::DiagnosticStatusWrapper status)
protected

A set of tasks to run before the tests:

  • Ensure we don't use the ROS interface during the tests (lock the mutexes).
Parameters
statusthe status of the pretest

Definition at line 455 of file real_shadowhand.cpp.

int16_t shadowrobot::RealShadowhand::sendupdate ( std::string  joint_name,
double  target 
)
virtual

Send a new target to a given joint on the robot. The command will be issued to the robot which will move if the controllers are started and tuned. The target is truncated to the correct range.

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 141 of file real_shadowhand.cpp.

int16_t shadowrobot::RealShadowhand::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 327 of file real_shadowhand.cpp.

int16_t shadowrobot::RealShadowhand::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 269 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::test_messages ( diagnostic_updater::DiagnosticStatusWrapper status)
protected

A test to check the number of messages received is the same as the number of messages sent. Calls the test_messages_routine for each joint / frequency we're testing.

Parameters
statusthe test result.

Definition at line 485 of file real_shadowhand.cpp.

std::pair< unsigned char, std::string > shadowrobot::RealShadowhand::test_messages_routine ( std::string  joint_name,
unsigned int  repeat,
ros::Rate  rate 
)
protected

The routine called during the test: test the number of received messages for a given joint, a given number of times and at a given frequency.

Parameters
joint_namethe name of the joint to test
repeatthe number of messages to send
ratethe rate at which we send the messages
Returns
a pair containing the status of the test (error or ok), and a message to display.

Definition at line 516 of file real_shadowhand.cpp.


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