Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
ArmMovementsByPoseAlgNode Class Reference

IRI ROS Specific Algorithm Class. More...

#include <arm_movements_by_pose_alg_node.h>

Inheritance diagram for ArmMovementsByPoseAlgNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ArmMovementsByPoseAlgNode (void)
 Constructor.
 ~ArmMovementsByPoseAlgNode (void)
 Destructor.

Protected Member Functions

void addNodeDiagnostics (void)
 node add diagnostics
void mainNodeThread (void)
 main node thread
void node_config_update (Config &config, uint32_t level)
 dynamic reconfigure server callback

Private Member Functions

bool clean_movementCallback (estirabot_msgs::ArmMovementsPosesSrv::Request &req, estirabot_msgs::ArmMovementsPosesSrv::Response &res)
void get_poses_markers (std::vector< geometry_msgs::PoseStamped > poses, std::vector< uint8_t > secondary_arm)
 Get markers showing the movements.
std::vector< double > get_wam_movement_speed ()
 gets array of vels or accs used by iri_wam_wrapper
bool move_armMakeActionRequest (bool right_arm, arm_navigation_msgs::SimplePoseConstraint desired_pose, std::string group_name)
void move_left_armActive ()
void move_left_armDone (const actionlib::SimpleClientGoalState &state, const arm_navigation_msgs::MoveArmResultConstPtr &result)
void move_left_armFeedback (const arm_navigation_msgs::MoveArmFeedbackConstPtr &feedback)
bool move_left_armMakeActionRequest (geometry_msgs::PoseStamped pose)
void move_right_armActive ()
void move_right_armDone (const actionlib::SimpleClientGoalState &state, const arm_navigation_msgs::MoveArmResultConstPtr &result)
void move_right_armFeedback (const arm_navigation_msgs::MoveArmFeedbackConstPtr &feedback)
bool move_right_armMakeActionRequest (geometry_msgs::PoseStamped pose)

Private Attributes

CMutex clean_movement_mutex_
ros::ServiceServer clean_movement_server_
bool fake_movements
ros::ServiceClient get_joints_from_pose_client_
iri_wam_common_msgs::wamInverseKinematics get_joints_from_pose_srv_
bool log_movements
std::ofstream logfile
visualization_msgs::MarkerArray MarkerArray_msg_
ros::ServiceClient move_in_joints_client_
iri_wam_common_msgs::joints_move move_in_joints_srv_
actionlib::SimpleActionClient
< arm_navigation_msgs::MoveArmAction
move_left_arm_client_
arm_navigation_msgs::MoveArmGoal move_left_arm_goal_
actionlib::SimpleActionClient
< arm_navigation_msgs::MoveArmAction
move_right_arm_client_
arm_navigation_msgs::MoveArmGoal move_right_arm_goal_
double pitch_rotation
ros::ServiceClient pose_move_client_
iri_wam_common_msgs::pose_move pose_move_srv_
double robot_movement_speed_
bool robot_wam
double roll_rotation
ros::Publisher visualization_movement_markers_publisher_
ros::ServiceClient wam_pose_move_client_
iri_wam_common_msgs::pose_move wam_pose_move_srv_
double yaw_rotation

Detailed Description

IRI ROS Specific Algorithm Class.

Definition at line 59 of file arm_movements_by_pose_alg_node.h.


Constructor & Destructor Documentation

Constructor.

This constructor initializes specific class attributes and all ROS communications variables to enable message exchange.

Definition at line 3 of file arm_movements_by_pose_alg_node.cpp.

Destructor.

This destructor frees all necessary dynamic memory allocated within this this class.

Definition at line 37 of file arm_movements_by_pose_alg_node.cpp.


Member Function Documentation

void ArmMovementsByPoseAlgNode::addNodeDiagnostics ( void  ) [protected, virtual]

node add diagnostics

In this abstract function additional ROS diagnostics applied to the specific algorithms may be added.

Implements algorithm_base::IriBaseAlgorithm< ArmMovementsByPoseAlgorithm >.

Definition at line 469 of file arm_movements_by_pose_alg_node.cpp.

bool ArmMovementsByPoseAlgNode::clean_movementCallback ( estirabot_msgs::ArmMovementsPosesSrv::Request &  req,
estirabot_msgs::ArmMovementsPosesSrv::Response &  res 
) [private]

Definition at line 93 of file arm_movements_by_pose_alg_node.cpp.

void ArmMovementsByPoseAlgNode::get_poses_markers ( std::vector< geometry_msgs::PoseStamped >  poses,
std::vector< uint8_t >  secondary_arm 
) [private]

Get markers showing the movements.

Shows markers for rviz showing the movements that the robot is going to perform

Definition at line 488 of file arm_movements_by_pose_alg_node.cpp.

gets array of vels or accs used by iri_wam_wrapper

Gets array of vels or accs used by iri_wam_wrapper. Returns an array containing 7 copies of robot_movement_speed_.

Definition at line 480 of file arm_movements_by_pose_alg_node.cpp.

void ArmMovementsByPoseAlgNode::mainNodeThread ( void  ) [protected, virtual]

main node thread

This is the main thread node function. Code written here will be executed in every node loop while the algorithm is on running state. Loop frequency can be tuned by modifying loop_rate attribute.

Here data related to the process loop or to ROS topics (mainly data structs related to the MSG and SRV files) must be updated. ROS publisher objects must publish their data in this process. ROS client servers may also request data to the corresponding server topics.

Implements algorithm_base::IriBaseAlgorithm< ArmMovementsByPoseAlgorithm >.

Definition at line 44 of file arm_movements_by_pose_alg_node.cpp.

bool ArmMovementsByPoseAlgNode::move_armMakeActionRequest ( bool  right_arm,
arm_navigation_msgs::SimplePoseConstraint  desired_pose,
std::string  group_name 
) [private]

Definition at line 377 of file arm_movements_by_pose_alg_node.cpp.

Definition at line 272 of file arm_movements_by_pose_alg_node.cpp.

Definition at line 262 of file arm_movements_by_pose_alg_node.cpp.

Definition at line 277 of file arm_movements_by_pose_alg_node.cpp.

bool ArmMovementsByPoseAlgNode::move_left_armMakeActionRequest ( geometry_msgs::PoseStamped  pose) [private]

Definition at line 333 of file arm_movements_by_pose_alg_node.cpp.

Definition at line 244 of file arm_movements_by_pose_alg_node.cpp.

Definition at line 234 of file arm_movements_by_pose_alg_node.cpp.

Definition at line 249 of file arm_movements_by_pose_alg_node.cpp.

bool ArmMovementsByPoseAlgNode::move_right_armMakeActionRequest ( geometry_msgs::PoseStamped  pose) [private]

Definition at line 294 of file arm_movements_by_pose_alg_node.cpp.

void ArmMovementsByPoseAlgNode::node_config_update ( Config config,
uint32_t  level 
) [protected, virtual]

dynamic reconfigure server callback

This method is called whenever a new configuration is received through the dynamic reconfigure. The derivated generic algorithm class must implement it.

Parameters:
configan object with new configuration from all algorithm parameters defined in the config file.
levelinteger referring the level in which the configuration has been changed.

Implements algorithm_base::IriBaseAlgorithm< ArmMovementsByPoseAlgorithm >.

Definition at line 571 of file arm_movements_by_pose_alg_node.cpp.


Member Data Documentation

Definition at line 71 of file arm_movements_by_pose_alg_node.h.

Definition at line 69 of file arm_movements_by_pose_alg_node.h.

Definition at line 104 of file arm_movements_by_pose_alg_node.h.

Definition at line 78 of file arm_movements_by_pose_alg_node.h.

iri_wam_common_msgs::wamInverseKinematics ArmMovementsByPoseAlgNode::get_joints_from_pose_srv_ [private]

Definition at line 79 of file arm_movements_by_pose_alg_node.h.

Definition at line 106 of file arm_movements_by_pose_alg_node.h.

std::ofstream ArmMovementsByPoseAlgNode::logfile [private]

Definition at line 111 of file arm_movements_by_pose_alg_node.h.

visualization_msgs::MarkerArray ArmMovementsByPoseAlgNode::MarkerArray_msg_ [private]

Definition at line 64 of file arm_movements_by_pose_alg_node.h.

Definition at line 76 of file arm_movements_by_pose_alg_node.h.

iri_wam_common_msgs::joints_move ArmMovementsByPoseAlgNode::move_in_joints_srv_ [private]

Definition at line 77 of file arm_movements_by_pose_alg_node.h.

Definition at line 93 of file arm_movements_by_pose_alg_node.h.

Definition at line 94 of file arm_movements_by_pose_alg_node.h.

Definition at line 86 of file arm_movements_by_pose_alg_node.h.

Definition at line 87 of file arm_movements_by_pose_alg_node.h.

Definition at line 107 of file arm_movements_by_pose_alg_node.h.

Definition at line 80 of file arm_movements_by_pose_alg_node.h.

iri_wam_common_msgs::pose_move ArmMovementsByPoseAlgNode::pose_move_srv_ [private]

Definition at line 81 of file arm_movements_by_pose_alg_node.h.

Definition at line 108 of file arm_movements_by_pose_alg_node.h.

Definition at line 105 of file arm_movements_by_pose_alg_node.h.

Definition at line 107 of file arm_movements_by_pose_alg_node.h.

Definition at line 63 of file arm_movements_by_pose_alg_node.h.

Definition at line 74 of file arm_movements_by_pose_alg_node.h.

iri_wam_common_msgs::pose_move ArmMovementsByPoseAlgNode::wam_pose_move_srv_ [private]

Definition at line 75 of file arm_movements_by_pose_alg_node.h.

Definition at line 107 of file arm_movements_by_pose_alg_node.h.


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


iri_arm_movements_by_pose
Author(s): David Martinez
autogenerated on Fri Dec 6 2013 20:39:32