#include <virtual_arm.h>
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 () | |
virtual | ~VirtualArm () |
Protected Member Functions | |
void | initializeMap () |
double | toDegrees (double rad) |
double | toRad (double deg) |
Definition at line 34 of file virtual_arm.h.
Initializes the necessary mappings with a static list of names.
Definition at line 40 of file virtual_arm.cpp.
shadowrobot::VirtualArm::~VirtualArm | ( | ) | [virtual] |
Definition at line 62 of file virtual_arm.cpp.
Get the data for all the joints.
Implements shadowrobot::SRArticulatedRobot.
Definition at line 220 of file virtual_arm.cpp.
void shadowrobot::VirtualArm::getConfig | ( | std::string | joint_name | ) | [virtual] |
Get the config of the palm
joint_name |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 263 of file virtual_arm.cpp.
JointControllerData shadowrobot::VirtualArm::getContrl | ( | std::string | contrlr_name | ) | [virtual] |
Get the controller parameters for a given controller name.
contrlr_name | the name of the controller. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 250 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).
Implements shadowrobot::SRArticulatedRobot.
Definition at line 268 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...)
joint_name | The name of the joint, as specified in joints_map. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 194 of file virtual_arm.cpp.
void shadowrobot::VirtualArm::initializeMap | ( | ) | [protected] |
Initialise a mapping for the joints.
Definition at line 66 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.
joint_name | The Joint in joints_map you wish to send the target to. |
target | The target in degree |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 154 of file virtual_arm.cpp.
short shadowrobot::VirtualArm::setConfig | ( | std::vector< std::string > | myConfig | ) | [virtual] |
Set the config of the palm
myConfig |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 257 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.
contrlr_name | The name of the controller to setup. |
ctrlr_data | The data to pass to this controller. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 244 of file virtual_arm.cpp.
double shadowrobot::VirtualArm::toDegrees | ( | double | rad | ) | [inline, protected] |
Convert an angle in radian to an angle in degrees.
rad | the angle in rads |
Definition at line 109 of file virtual_arm.h.
double shadowrobot::VirtualArm::toRad | ( | double | deg | ) | [inline, protected] |
Convert an angle in degree to an angle in radians.
deg | the angle in degrees |
Definition at line 99 of file virtual_arm.h.