#include <ArmComponentsNameManager.h>
Public Member Functions | |
ArmComponentsNameManager (const std::string &robot_namespace, bool readParams) | |
ArmComponentsNameManager (const ArmComponentsNameManager &o) | |
int | armJointNumber (const std::string &name) const |
void | copyToJointState (sensor_msgs::JointState &js, int mode, const std::vector< float > *init_vals, int copyData, bool resetAll) const |
bool | defaultsLoaded () |
bool | extractFromJointState (const sensor_msgs::JointState &js, int mode, std::vector< float > &data, int extractData) const |
bool | extractFromJointState (const sensor_msgs::JointState &js, int mode, sensor_msgs::JointState &result) const |
const std::vector< std::string > & | getArmJoints () const |
const std::vector< float > & | getArmJointsInitPose () const |
const std::vector< std::string > & | getArmLinks () const |
const std::string & | getEffectorLink () const |
const std::vector< std::string > & | getGripperJoints () const |
const std::vector< float > & | getGripperJointsInitPose () const |
const std::vector< std::string > & | getGripperLinks () const |
int | getJointIndices (const std::vector< std::string > &joint_names, std::vector< int > &idx) const |
bool | getJointIndices (const std::vector< std::string > &joint_names, std::vector< int > &idx, int mode) const |
void | getJointNames (std::vector< std::string > &joint_names, bool withGripper, const std::string &prepend=std::string()) const |
virtual bool | GetMaxVals (const std::string &jointName, float &force, float &velocity) const |
const std::string & | getPalmLink () const |
bool | GetPosGains (const std::string &jointName, float &kp, float &ki, float &kd) const |
bool | GetVelGains (const std::string &jointName, float &kp, float &ki, float &kd) const |
int | gripperJointNumber (const std::string &name) const |
virtual bool | hasDefaults () |
bool | isGripper (const std::string &name) const |
bool | loadDefaults () |
int | loadParameters (bool printErrors=true, bool verbose=false) |
int | numArmJoints () const |
int | numGripperJoints () const |
int | numTotalJoints () const |
int | parametersLoaded () |
void | ReadPIDValues (const std::string &pidParameterName, float &kp, float &ki, float &kd) const |
void | setControllerNames (const std::vector< std::string > &controller_names, bool forArm, int type) |
void | setValues (const std::string &_palm_link, const std::string &_effector_link, const std::vector< std::string > &_arm_joints, const std::vector< std::string > &_arm_links, const std::vector< std::string > &_gripper_joints, const std::vector< std::string > &_gripper_links, const std::vector< float > &_arm_joint_init, const std::vector< float > &_gripper_joint_init) |
bool | waitToLoadParameters (int sufficientSuccessCode, float maxWait, float waitStep=0.1) |
Protected Member Functions | |
virtual std::vector< std::string > | getDefaultArmJoints () const |
virtual std::vector< float > | getDefaultArmJointsInitPose () const |
virtual std::vector< float > | getDefaultArmJointsMaxForce () const |
virtual std::vector< float > | getDefaultArmJointsMaxVel () const |
virtual std::vector< std::string > | getDefaultArmLinks () const |
virtual std::string | getDefaultEffectorLink () const |
virtual std::vector< std::string > | getDefaultGripperJoints () const |
virtual std::vector< float > | getDefaultGripperJointsInitPose () const |
virtual std::vector< float > | getDefaultGripperJointsMaxForce () const |
virtual std::vector< float > | getDefaultGripperJointsMaxVel () const |
virtual std::vector< std::string > | getDefaultGripperLinks () const |
virtual std::string | getDefaultPalmLink () const |
Private Member Functions | |
ArmComponentsNameManager () | |
Private Attributes | |
std::vector< std::string > | arm_effort_controller_names |
std::vector< float > | arm_joint_init |
std::vector< float > | arm_joint_max_force |
std::vector< float > | arm_joint_max_vel |
std::vector< std::string > | arm_joints |
std::vector< std::string > | arm_links |
std::vector< std::string > | arm_position_controller_names |
std::vector< std::string > | arm_velocity_controller_names |
std::string | effector_link |
std::vector< std::string > | gripper_effort_controller_names |
std::vector< float > | gripper_joint_init |
std::vector< float > | gripper_joint_max_force |
std::vector< float > | gripper_joint_max_vel |
std::vector< std::string > | gripper_joints |
std::vector< std::string > | gripper_links |
std::vector< std::string > | gripper_position_controller_names |
std::vector< std::string > | gripper_velocity_controller_names |
int | initParamCode |
bool | initWithDefaults |
std::string | palm_link |
std::string | robot_namespace |
Manages information about the for a robotic "arm" as defined in the URDF file. The "robotic arm" is the kinematic chain which is used to reach to objects and grasp or manipulate them. It usually includes a gripper or hand to grasp the objects. This manager can be used to manage all sorts of properties which are specified per-joint or per-link. For example, it can also be used to manage PID values.
This class reads its parameters from the ROS parameter server in the function loadParameters(). Load the paramters on the ROS parameter server before calling loadParameters(), e.g. as follows from a launch file:
``` <arg name="names_config_file" default="$(find <your-package>)/config/<your-config>.yaml"> <rosparam command="load" file="$(arg names_config_file)"> ```
Parameters have to be specified like in this documented .yaml template:
``rosed arm_components_name_manager JointsTemplate.yaml``
This class can also be manually initialized with default values which take effect if the ROS parameters are not set. The values may be set manually by setValues() and setControllerNames(); alternatively, a subclass may be derived to provide default values by implementing getDefault* methods. The defaults can then be loaded by loadDefaults().
**Optional: Access per-joint PID values**
To use this class to manage PID values (which is optional), you have to specify the *effort_controller_names*, *position_controller_names* and *velocity_controller_names* lists in the yaml file. These "controller names" are to be the ones used in another configuration file, which has to be in the format also used by ros_control. For example, for a velocity controller, this could be a PID values config file (lets name it PIDConfig.yaml):
``` <joint_name>_velocity_controller: type: velocity_controllers/JointVelocityController joint: <joint_name> pid: {p: 10, i: 0.0001, d: 0.005} ```
In this example, the configuration file (e.g. JointsTemplate.yaml) has to include this:
``` velocity_controller_names:
The names config file (JointsTemplate.yaml) only needs a list of those joint controller names, not the actual PID values. It is assumed that each robot only has *one* velocity, effort or position controller per joint, which is then referred to globally with the same name. The actual PID values may be loaded on the parameter server *after* an instance of this class has already been created. The names in the lists are only needed to look up the right controller values at the time when functions GetPosGains() and GetVelGains() are called to read from the parameter server. Current limitation: The namespace in the JointsTemplate.yaml config file has to be the same as the namespace used in the PID values PIDConfig.yaml file.
Definition at line 100 of file ArmComponentsNameManager.h.
ArmComponentsNameManager::ArmComponentsNameManager | ( | const std::string & | robot_namespace, |
bool | readParams | ||
) |
Initializes joint names by reading from parameter server.
readParams | if true, the method loadParameters() is called from within the constructor. If false, the paramters may be loaded later by calling function loadParameters(). namespace of the robot which needs to be used in the YAML file |
Definition at line 31 of file ArmComponentsNameManager.cpp.
Definition at line 41 of file ArmComponentsNameManager.cpp.
int ArmComponentsNameManager::armJointNumber | ( | const std::string & | name | ) | const |
Returns the number of the joint in the arm, or -1 if this is no arm joint. Numbering starts with 0.
Definition at line 713 of file ArmComponentsNameManager.cpp.
void ArmComponentsNameManager::copyToJointState | ( | sensor_msgs::JointState & | js, |
int | mode, | ||
const std::vector< float > * | init_vals, | ||
int | copyData, | ||
bool | resetAll | ||
) | const |
Joint names as to be used in the default order (e.g. for JointState messsages)
init_poses | (optional) if specified, you can set the target angles of the joint positions here. The order has to be standard, as returned by getJointNames(). Copy names (and optionally data fields) into the JointState js. Joint names as to be used in the default order (e.g. for JointState messsages). Existing joint state names will be cleared before being re-initialized. |
mode | which names to copy int . 0 = all joints (first arm, then gripper joints will be inserted in angles); 1 = only arm joints; 2 = only gripper joints. |
init_vals | (optional) if specified, you can set the target values of the joint positions here. The order has to be according to mode. |
copyData | specifies which type of data init_vals contains: if 0, positions. If 1, velocities. If 2, efforts. |
resetOthers | set this to true to reset all positon, velocities and efforts and just resize them to correct size and initialize them to 0. If init_vals is set, this will still override the 0 init values. |
Definition at line 484 of file ArmComponentsNameManager.cpp.
bool arm_components_name_manager::ArmComponentsNameManager::defaultsLoaded | ( | ) | [inline] |
returns true if defaults were successfully loaded with loadDefaults()
Definition at line 155 of file ArmComponentsNameManager.h.
bool ArmComponentsNameManager::extractFromJointState | ( | const sensor_msgs::JointState & | js, |
int | mode, | ||
std::vector< float > & | data, | ||
int | extractData | ||
) | const |
Extracts all arm and/or gripper values (according to extractData), in the standardized order, from a JointState message.
mode | which data to extract. 0 = all joints (first arm, then gripper joints will be inserted in angles); 1 = only arm joints; 2 = only gripper joints. |
extractData | if 0, extract positions. If 1, extract velocities. If 2, extract efforts. |
false | extraction not successfull because not all data was available in joint state js |
Definition at line 526 of file ArmComponentsNameManager.cpp.
bool ArmComponentsNameManager::extractFromJointState | ( | const sensor_msgs::JointState & | js, |
int | mode, | ||
sensor_msgs::JointState & | result | ||
) | const |
Definition at line 596 of file ArmComponentsNameManager.cpp.
const std::vector< std::string > & ArmComponentsNameManager::getArmJoints | ( | ) | const |
Definition at line 447 of file ArmComponentsNameManager.cpp.
const std::vector< float > & ArmComponentsNameManager::getArmJointsInitPose | ( | ) | const |
Definition at line 456 of file ArmComponentsNameManager.cpp.
const std::vector< std::string > & ArmComponentsNameManager::getArmLinks | ( | ) | const |
Get all links for the arm, *excluding* the palm link
Definition at line 441 of file ArmComponentsNameManager.cpp.
virtual std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::getDefaultArmJoints | ( | ) | const [inline, protected, virtual] |
Definition at line 355 of file ArmComponentsNameManager.h.
virtual std::vector<float> arm_components_name_manager::ArmComponentsNameManager::getDefaultArmJointsInitPose | ( | ) | const [inline, protected, virtual] |
Definition at line 359 of file ArmComponentsNameManager.h.
virtual std::vector<float> arm_components_name_manager::ArmComponentsNameManager::getDefaultArmJointsMaxForce | ( | ) | const [inline, protected, virtual] |
Definition at line 362 of file ArmComponentsNameManager.h.
virtual std::vector<float> arm_components_name_manager::ArmComponentsNameManager::getDefaultArmJointsMaxVel | ( | ) | const [inline, protected, virtual] |
Definition at line 361 of file ArmComponentsNameManager.h.
virtual std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::getDefaultArmLinks | ( | ) | const [inline, protected, virtual] |
Definition at line 356 of file ArmComponentsNameManager.h.
virtual std::string arm_components_name_manager::ArmComponentsNameManager::getDefaultEffectorLink | ( | ) | const [inline, protected, virtual] |
Definition at line 354 of file ArmComponentsNameManager.h.
virtual std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::getDefaultGripperJoints | ( | ) | const [inline, protected, virtual] |
Definition at line 357 of file ArmComponentsNameManager.h.
virtual std::vector<float> arm_components_name_manager::ArmComponentsNameManager::getDefaultGripperJointsInitPose | ( | ) | const [inline, protected, virtual] |
Definition at line 360 of file ArmComponentsNameManager.h.
virtual std::vector<float> arm_components_name_manager::ArmComponentsNameManager::getDefaultGripperJointsMaxForce | ( | ) | const [inline, protected, virtual] |
Definition at line 364 of file ArmComponentsNameManager.h.
virtual std::vector<float> arm_components_name_manager::ArmComponentsNameManager::getDefaultGripperJointsMaxVel | ( | ) | const [inline, protected, virtual] |
Definition at line 363 of file ArmComponentsNameManager.h.
virtual std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::getDefaultGripperLinks | ( | ) | const [inline, protected, virtual] |
Definition at line 358 of file ArmComponentsNameManager.h.
virtual std::string arm_components_name_manager::ArmComponentsNameManager::getDefaultPalmLink | ( | ) | const [inline, protected, virtual] |
Definition at line 353 of file ArmComponentsNameManager.h.
const std::string & ArmComponentsNameManager::getEffectorLink | ( | ) | const |
Returns name of the link which is considered to be the end effector which is used to position the effector before grasping objects. Defaults to palm_link if not specified in ROS parameters.
Definition at line 436 of file ArmComponentsNameManager.cpp.
const std::vector< std::string > & ArmComponentsNameManager::getGripperJoints | ( | ) | const |
Definition at line 451 of file ArmComponentsNameManager.cpp.
const std::vector< float > & ArmComponentsNameManager::getGripperJointsInitPose | ( | ) | const |
Definition at line 460 of file ArmComponentsNameManager.cpp.
const std::vector< std::string > & ArmComponentsNameManager::getGripperLinks | ( | ) | const |
returns all gripper links *excluding* the palm link link
Definition at line 426 of file ArmComponentsNameManager.cpp.
int ArmComponentsNameManager::getJointIndices | ( | const std::vector< std::string > & | joint_names, |
std::vector< int > & | idx | ||
) | const |
Helper function to find out the order of joints given in a names vector. Returns in output vector idx the indices of arm and/or gripper joints in the joint_names vector.
-1 | error if not all arm or all gripper joints are present in joint_names. Required are either all arm joints, or all gripper joints, or both arm and gripper joints. |
0 | if all joints present. Then, idx is of size numArmJoints() + numGripperJoints(), and the indices contain first the arm joints, then the gripper joints. |
1 | if only arm joints present. Then, idx is of size numArmJoints(). |
2 | if only gripper joints present. Then, idx is of size numGripperJoints(). |
If only one group is present, the indices for the other group in idx are going to be set to -1.
Definition at line 645 of file ArmComponentsNameManager.cpp.
bool ArmComponentsNameManager::getJointIndices | ( | const std::vector< std::string > & | joint_names, |
std::vector< int > & | idx, | ||
int | mode | ||
) | const |
Like other getJointIndices(), but allows to get joint indices for a particular group, according to mode.
mode | if 0, get indices for both arm and gripper joints. If 1, get only arm joints. If 2, get only gripper joints. |
Definition at line 608 of file ArmComponentsNameManager.cpp.
void ArmComponentsNameManager::getJointNames | ( | std::vector< std::string > & | joint_names, |
bool | withGripper, | ||
const std::string & | prepend = std::string() |
||
) | const |
Joint names as to be used in the default order (e.g. for JointState messsages)
prepend | if not empty, this string is going to be prepended to the joint names |
Definition at line 411 of file ArmComponentsNameManager.cpp.
bool ArmComponentsNameManager::GetMaxVals | ( | const std::string & | jointName, |
float & | force, | ||
float & | velocity | ||
) | const [virtual] |
Returns the max values for this joint.
Definition at line 371 of file ArmComponentsNameManager.cpp.
const std::string & ArmComponentsNameManager::getPalmLink | ( | ) | const |
Returns the link which counts as the "palm", which is the link to which all gripper joints are attached. This link should be the link directly before the gripper joints. There should be **no other movable joints between the palm link and the gripper joints**. The palm link lies between the last joint in arm_joints and before all joints in gripper_joints.
Definition at line 431 of file ArmComponentsNameManager.cpp.
bool ArmComponentsNameManager::GetPosGains | ( | const std::string & | jointName, |
float & | kp, | ||
float & | ki, | ||
float & | kd | ||
) | const |
Calls ReadPIDValues() for the position controller for the joint specified in jointName. If the joint is not found, the values of paramters kp,ki and kd are left as they are, so ideally they should be initialzied with defaults before calling this function.
Definition at line 307 of file ArmComponentsNameManager.cpp.
bool ArmComponentsNameManager::GetVelGains | ( | const std::string & | jointName, |
float & | kp, | ||
float & | ki, | ||
float & | kd | ||
) | const |
Like GetPosGains(), but for velocity controller.
Definition at line 339 of file ArmComponentsNameManager.cpp.
int ArmComponentsNameManager::gripperJointNumber | ( | const std::string & | name | ) | const |
Returns the number of the joint of the grippers, or -1 if this is no gripper joint. Numbering starts with 0.
Definition at line 723 of file ArmComponentsNameManager.cpp.
virtual bool arm_components_name_manager::ArmComponentsNameManager::hasDefaults | ( | ) | [inline, virtual] |
return true in subclasses which provides all the defaults in the getDefault*() methods.
Definition at line 346 of file ArmComponentsNameManager.h.
bool ArmComponentsNameManager::isGripper | ( | const std::string & | name | ) | const |
Check whether this is a gripper joint
Definition at line 703 of file ArmComponentsNameManager.cpp.
Loads default values as given by the implementation. Controller names have no defaults but can be initialized manually with setControllerNames().
Definition at line 61 of file ArmComponentsNameManager.cpp.
int ArmComponentsNameManager::loadParameters | ( | bool | printErrors = true , |
bool | verbose = false |
||
) |
Reads from the private parameter server according to specification in the example .yaml file. This will override any values which were set by loadDefaults()!
-1 | none of the parameters was found on ROS parameter server |
0 | some of the parameters were found on ROS parameter server. The existing values were loaded. |
1 | All mandatory parameters found on parameter server and loaded. |
2 | All mandatory parameters AND controller names found on parameter server and loaded. |
Definition at line 78 of file ArmComponentsNameManager.cpp.
int ArmComponentsNameManager::numArmJoints | ( | ) | const |
Definition at line 733 of file ArmComponentsNameManager.cpp.
int ArmComponentsNameManager::numGripperJoints | ( | ) | const |
Definition at line 738 of file ArmComponentsNameManager.cpp.
int arm_components_name_manager::ArmComponentsNameManager::numTotalJoints | ( | ) | const [inline] |
Definition at line 261 of file ArmComponentsNameManager.h.
Check if the parameters were loaded. Same return values as loadParameters().
Definition at line 147 of file ArmComponentsNameManager.h.
void ArmComponentsNameManager::ReadPIDValues | ( | const std::string & | pidParameterName, |
float & | kp, | ||
float & | ki, | ||
float & | kd | ||
) | const |
Reads PID parameters from the ROS parameter server, where they are stored as a dictionary as follows:
pid: p: <p-value> i: <i-value> d: <d-value>
Definition at line 289 of file ArmComponentsNameManager.cpp.
void ArmComponentsNameManager::setControllerNames | ( | const std::vector< std::string > & | controller_names, |
bool | forArm, | ||
int | type | ||
) |
Sets the names of the controllers as they would otherwise be specified in the YAML file.
bool | forArm set the names for the arm (if false, for the gripper) |
type | type of controller: 0 = effort, 1 = velocity, 2 = position |
Definition at line 761 of file ArmComponentsNameManager.cpp.
void ArmComponentsNameManager::setValues | ( | const std::string & | _palm_link, |
const std::string & | _effector_link, | ||
const std::vector< std::string > & | _arm_joints, | ||
const std::vector< std::string > & | _arm_links, | ||
const std::vector< std::string > & | _gripper_joints, | ||
const std::vector< std::string > & | _gripper_links, | ||
const std::vector< float > & | _arm_joint_init, | ||
const std::vector< float > & | _gripper_joint_init | ||
) |
Sets the names fo all joints, links, and initial poses which otherwise would be specified in the YAML file.
_palm_link | name of the palm link. See also description in getPalmLink(). |
_arm_joints | names of the arm joints *without* the gripper joints. |
_arm_links | all links which are in-between (and directly before and after) the arm_joints. It does however *not* include the palm_link. |
_gripper_joints | All joints of the "gripper" |
_gripper_links | All links of the "gripper". It does however *not* include the palm_link. |
_arm_joint_init | initial ("Home") pose of the arm joints. Has to be the same order as _arm_joints. |
_gripper_joint_init | initial ("Home") pose of the gripper joints. Has to be the same order as _gripper_joints. |
Definition at line 744 of file ArmComponentsNameManager.cpp.
bool ArmComponentsNameManager::waitToLoadParameters | ( | int | sufficientSuccessCode, |
float | maxWait, | ||
float | waitStep = 0.1 |
||
) |
wait for maximum maxWait seconds and keep re-trying to laod parameters by calling loadParameters(). This has been considered successful when returning values greater than sufficientSuccessCode.
sufficientSuccessCode | return value of loadParameters() which is considered a success and can stop the waiting. |
waitStep | the amount of seconds to sleep in-between re-checking for parameters |
Definition at line 274 of file ArmComponentsNameManager.cpp.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::arm_effort_controller_names [private] |
Definition at line 448 of file ArmComponentsNameManager.h.
std::vector<float> arm_components_name_manager::ArmComponentsNameManager::arm_joint_init [private] |
initial ("Home") pose of the arm joints. Has to be the same order as arm_joints.
Definition at line 423 of file ArmComponentsNameManager.h.
std::vector<float> arm_components_name_manager::ArmComponentsNameManager::arm_joint_max_force [private] |
Maximum force of the arm joints
Definition at line 438 of file ArmComponentsNameManager.h.
std::vector<float> arm_components_name_manager::ArmComponentsNameManager::arm_joint_max_vel [private] |
Maximum velocity of the arm joints
Definition at line 434 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::arm_joints [private] |
Names of the arm joints *without* the gripper joints. These are the joints which are used to move the arm in pre-grasp state, but which are *not* part of the acutal gripper (essentially an arm without the grippers)
Definition at line 376 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::arm_links [private] |
All links which are in-between (and directly before and after) the arm_joints. It does however *not* include the palm_link because this is specified separately.
Definition at line 383 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::arm_position_controller_names [private] |
Definition at line 450 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::arm_velocity_controller_names [private] |
Definition at line 449 of file ArmComponentsNameManager.h.
std::string arm_components_name_manager::ArmComponentsNameManager::effector_link [private] |
name of the link which is considered to be the end effector which is used to position the effector before grasping objects. Defaults to palm_link if not specified.
Definition at line 417 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::gripper_effort_controller_names [private] |
Definition at line 452 of file ArmComponentsNameManager.h.
std::vector<float> arm_components_name_manager::ArmComponentsNameManager::gripper_joint_init [private] |
initial ("Home") pose of the gripper joints. Has to be the same order as gripper_joints.
Definition at line 429 of file ArmComponentsNameManager.h.
std::vector<float> arm_components_name_manager::ArmComponentsNameManager::gripper_joint_max_force [private] |
Maximum force of the gripper joints
Definition at line 446 of file ArmComponentsNameManager.h.
std::vector<float> arm_components_name_manager::ArmComponentsNameManager::gripper_joint_max_vel [private] |
Maximum velocity of the gripper joints
Definition at line 442 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::gripper_joints [private] |
All joints of the "gripper". The gripper is the part of the arm used to grasp/grip objects. Essentially, they are the "gripper joints".
Definition at line 390 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::gripper_links [private] |
All links which are in-between (and directly before and after) the gripper_joints. It does however *not* include the palm_link because this is specified separately.
Definition at line 398 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::gripper_position_controller_names [private] |
Definition at line 454 of file ArmComponentsNameManager.h.
std::vector<std::string> arm_components_name_manager::ArmComponentsNameManager::gripper_velocity_controller_names [private] |
Definition at line 453 of file ArmComponentsNameManager.h.
Initialization code. value: -1 none of the parameters was found on ROS parameter server value: 0 some of the parameters were found on ROS parameter server. The existing values were loaded. value: 1 All mandatory parameters found on parameter server and loaded. value: 2 All mandatory parameters AND controller names found on parameter server and loaded.
Definition at line 466 of file ArmComponentsNameManager.h.
true if the defaults were loaded.
Definition at line 471 of file ArmComponentsNameManager.h.
std::string arm_components_name_manager::ArmComponentsNameManager::palm_link [private] |
Name of the palm link. This is the link to which objects that this end effector grasps are symbolically "attached" when the object is grasped. This link should be the link directly before the gripper joints. There should be **no other movable joints between the palm link and the gripper joints**. The palm link lies between the last joint in arm_joints and before all joints in gripper_joints.
Definition at line 410 of file ArmComponentsNameManager.h.
std::string arm_components_name_manager::ArmComponentsNameManager::robot_namespace [private] |
Definition at line 456 of file ArmComponentsNameManager.h.