IRI ROS Specific Driver Class. More...
#include <wam_arm_navigation_alg.h>
Public Types | |
typedef iri_wam_arm_navigation::WamArmNavigationConfig | Config |
define config type | |
Public Member Functions | |
void | addGoalConstraintToMoveArmGoal (const arm_navigation_msgs::SimplePoseConstraint &pose_constraint, arm_navigation_msgs::MoveArmGoal &move_arm_goal) |
void | config_update (Config &new_cfg, uint32_t level=0) |
config update | |
bool | hasPose () |
void | lock (void) |
Lock Algorithm. | |
void | sendedPose () |
void | setPlannerRequest (arm_navigation_msgs::MoveArmGoal &goal) |
Defined Motion Request Parameters. | |
void | setPlannerRequestPose (arm_navigation_msgs::MoveArmGoal &goal) |
Defined Goal Constraint Parameters. | |
void | setTarget (const geometry_msgs::PoseStamped &pose, const std::string &nameFrame) |
bool | try_enter (void) |
Tries Access to Algorithm. | |
void | unlock (void) |
Unlock Algorithm. | |
WamArmNavigationAlgorithm (void) | |
constructor | |
~WamArmNavigationAlgorithm (void) | |
Destructor. | |
Public Attributes | |
Config | config_ |
config variable | |
std::string | frame_id_target |
bool | has_pose |
geometry_msgs::PoseStamped | pose_goal |
Protected Attributes | |
CMutex | alg_mutex_ |
define config type |
IRI ROS Specific Driver Class.
Definition at line 44 of file wam_arm_navigation_alg.h.
typedef iri_wam_arm_navigation::WamArmNavigationConfig WamArmNavigationAlgorithm::Config |
define config type
Define a Config type with the WamArmNavigationConfig. All driver implementations will then use the same variable type Config.
Definition at line 64 of file wam_arm_navigation_alg.h.
constructor
In this constructor parameters related to the specific driver can be initalized. Those parameters can be also set in the openDriver() function. Attributes from the main node driver class IriBaseDriver such as loop_rate, may be also overload here.
Definition at line 3 of file wam_arm_navigation_alg.cpp.
Destructor.
This destructor is called when the object is about to be destroyed.
Definition at line 9 of file wam_arm_navigation_alg.cpp.
void WamArmNavigationAlgorithm::addGoalConstraintToMoveArmGoal | ( | const arm_navigation_msgs::SimplePoseConstraint & | pose_constraint, |
arm_navigation_msgs::MoveArmGoal & | move_arm_goal | ||
) |
Definition at line 73 of file wam_arm_navigation_alg.cpp.
void WamArmNavigationAlgorithm::config_update | ( | Config & | new_cfg, |
uint32_t | level = 0 |
||
) |
config update
In this function the driver parameters must be updated with the input config variable. Then the new configuration state will be stored in the Config attribute.
new_cfg | the new driver configuration state |
level | level in which the update is taken place |
Definition at line 13 of file wam_arm_navigation_alg.cpp.
Definition at line 30 of file wam_arm_navigation_alg.cpp.
void WamArmNavigationAlgorithm::lock | ( | void | ) | [inline] |
Lock Algorithm.
Locks access to the Algorithm class
Definition at line 89 of file wam_arm_navigation_alg.h.
Definition at line 34 of file wam_arm_navigation_alg.cpp.
Defined Motion Request Parameters.
Definition at line 39 of file wam_arm_navigation_alg.cpp.
Defined Goal Constraint Parameters.
Definition at line 51 of file wam_arm_navigation_alg.cpp.
void WamArmNavigationAlgorithm::setTarget | ( | const geometry_msgs::PoseStamped & | pose, |
const std::string & | nameFrame | ||
) |
Definition at line 24 of file wam_arm_navigation_alg.cpp.
bool WamArmNavigationAlgorithm::try_enter | ( | void | ) | [inline] |
Tries Access to Algorithm.
Tries access to Algorithm
Definition at line 105 of file wam_arm_navigation_alg.h.
void WamArmNavigationAlgorithm::unlock | ( | void | ) | [inline] |
Unlock Algorithm.
Unlocks access to the Algorithm class
Definition at line 96 of file wam_arm_navigation_alg.h.
CMutex WamArmNavigationAlgorithm::alg_mutex_ [protected] |
define config type
Define a Config type with the WamArmNavigationConfig. All driver implementations will then use the same variable type Config.
Definition at line 53 of file wam_arm_navigation_alg.h.
config variable
This variable has all the driver parameters defined in the cfg config file. Is updated everytime function config_update() is called.
Definition at line 72 of file wam_arm_navigation_alg.h.
std::string WamArmNavigationAlgorithm::frame_id_target |
Definition at line 132 of file wam_arm_navigation_alg.h.
Definition at line 133 of file wam_arm_navigation_alg.h.
geometry_msgs::PoseStamped WamArmNavigationAlgorithm::pose_goal |
Definition at line 131 of file wam_arm_navigation_alg.h.