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

IRI ROS Specific Algorithm Class. More...

#include <convert_pose_alg_node.h>

Inheritance diagram for ConvertPoseAlgNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ConvertPoseAlgNode (void)
 Constructor.
 ~ConvertPoseAlgNode (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

void adc_channels_callback (const std_msgs::Float64MultiArray::ConstPtr &msg)
void joint_state_callback (const sensor_msgs::JointState::ConstPtr &msg)
void marker_callback (const ar_pose::ARMarkers::ConstPtr &msg)
void move_jointsActive ()
void move_jointsDone (const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
void move_jointsFeedback (const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
void move_jointsMakeActionRequest ()
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)
void move_left_armMakeActionRequest ()
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)
void move_right_armMakeActionRequest ()
void tracking_headActive ()
void tracking_headDone (const actionlib::SimpleClientGoalState &state, const iri_darwin_robot::tracking_headResultConstPtr &result)
void tracking_headFeedback (const iri_darwin_robot::tracking_headFeedbackConstPtr &feedback)
void tracking_headMakeActionRequest ()

Private Attributes

CMutex adc_channels_mutex_
ros::Subscriber adc_channels_subscriber_
ros::Publisher cmd_vel_publisher_
geometry_msgs::PoseStamped conv_msg_
double current_pan
sensor_msgs::JointState current_state
double current_voltage
ros::Publisher execute_action_publisher_
bool first_goal
std_msgs::Float64MultiArray Float64MultiArray_msg_
ros::ServiceClient get_ik_client_
kinematics_msgs::GetPositionIK get_ik_srv_
bool head_moving
ros::Publisher head_target_publisher_
std_msgs::Int32 Int32_msg_
CMutex joint_state_mutex_
ros::Subscriber joint_state_subscriber_
bool joints_moving
bool left_arm_moving
bool left_data_ready
bool left_done
bool left_marker_found
bool left_ok
geometry_msgs::PoseStamped left_pose_
bool left_ready_tf
geometry_msgs::PoseStamped marker_
CMutex marker_mutex_
ros::Subscriber marker_subscriber_
actionlib::SimpleActionClient
< control_msgs::FollowJointTrajectoryAction
move_joints_client_
control_msgs::FollowJointTrajectoryGoal move_joints_goal_
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_
ar_pose::ARMarkers msg_
int n
bool prev_left_ok
bool prev_right_ok
bool ready
bool ready_for_check
bool right_arm_moving
bool right_data_ready
bool right_marker_found
bool right_ok
geometry_msgs::PoseStamped right_pose_
bool right_ready_tf
TStates state
bool success
tf::TransformListener tf_listener
actionlib::SimpleActionClient
< iri_darwin_robot::tracking_headAction
tracking_head_client_
iri_darwin_robot::tracking_headGoal tracking_head_goal_
geometry_msgs::Twist Twist_msg_

Detailed Description

IRI ROS Specific Algorithm Class.

Definition at line 60 of file convert_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 convert_pose_alg_node.cpp.

Destructor.

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

Definition at line 58 of file convert_pose_alg_node.cpp.


Member Function Documentation

void ConvertPoseAlgNode::adc_channels_callback ( const std_msgs::Float64MultiArray::ConstPtr &  msg) [private]

Definition at line 797 of file convert_pose_alg_node.cpp.

void ConvertPoseAlgNode::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< ConvertPoseAlgorithm >.

Definition at line 1134 of file convert_pose_alg_node.cpp.

void ConvertPoseAlgNode::joint_state_callback ( const sensor_msgs::JointState::ConstPtr &  msg) [private]

Definition at line 812 of file convert_pose_alg_node.cpp.

void ConvertPoseAlgNode::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< ConvertPoseAlgorithm >.

Definition at line 63 of file convert_pose_alg_node.cpp.

void ConvertPoseAlgNode::marker_callback ( const ar_pose::ARMarkers::ConstPtr &  msg) [private]

Definition at line 826 of file convert_pose_alg_node.cpp.

Definition at line 966 of file convert_pose_alg_node.cpp.

Definition at line 955 of file convert_pose_alg_node.cpp.

Definition at line 971 of file convert_pose_alg_node.cpp.

Definition at line 1072 of file convert_pose_alg_node.cpp.

Definition at line 1032 of file convert_pose_alg_node.cpp.

Definition at line 1021 of file convert_pose_alg_node.cpp.

Definition at line 1037 of file convert_pose_alg_node.cpp.

Definition at line 1108 of file convert_pose_alg_node.cpp.

Definition at line 999 of file convert_pose_alg_node.cpp.

Definition at line 988 of file convert_pose_alg_node.cpp.

Definition at line 1004 of file convert_pose_alg_node.cpp.

Definition at line 1090 of file convert_pose_alg_node.cpp.

void ConvertPoseAlgNode::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< ConvertPoseAlgorithm >.

Definition at line 1127 of file convert_pose_alg_node.cpp.

Definition at line 934 of file convert_pose_alg_node.cpp.

Definition at line 924 of file convert_pose_alg_node.cpp.

Definition at line 939 of file convert_pose_alg_node.cpp.

Definition at line 1055 of file convert_pose_alg_node.cpp.


Member Data Documentation

Definition at line 74 of file convert_pose_alg_node.h.

Definition at line 72 of file convert_pose_alg_node.h.

Definition at line 64 of file convert_pose_alg_node.h.

geometry_msgs::PoseStamped ConvertPoseAlgNode::conv_msg_ [private]

Definition at line 84 of file convert_pose_alg_node.h.

Definition at line 146 of file convert_pose_alg_node.h.

sensor_msgs::JointState ConvertPoseAlgNode::current_state [private]

Definition at line 79 of file convert_pose_alg_node.h.

Definition at line 75 of file convert_pose_alg_node.h.

Definition at line 68 of file convert_pose_alg_node.h.

Definition at line 144 of file convert_pose_alg_node.h.

std_msgs::Float64MultiArray ConvertPoseAlgNode::Float64MultiArray_msg_ [private]

Definition at line 67 of file convert_pose_alg_node.h.

Definition at line 92 of file convert_pose_alg_node.h.

kinematics_msgs::GetPositionIK ConvertPoseAlgNode::get_ik_srv_ [private]

Definition at line 93 of file convert_pose_alg_node.h.

Definition at line 131 of file convert_pose_alg_node.h.

Definition at line 66 of file convert_pose_alg_node.h.

Definition at line 69 of file convert_pose_alg_node.h.

Definition at line 78 of file convert_pose_alg_node.h.

Definition at line 76 of file convert_pose_alg_node.h.

Definition at line 111 of file convert_pose_alg_node.h.

Definition at line 127 of file convert_pose_alg_node.h.

Definition at line 135 of file convert_pose_alg_node.h.

Definition at line 136 of file convert_pose_alg_node.h.

Definition at line 132 of file convert_pose_alg_node.h.

Definition at line 138 of file convert_pose_alg_node.h.

geometry_msgs::PoseStamped ConvertPoseAlgNode::left_pose_ [private]

Definition at line 86 of file convert_pose_alg_node.h.

Definition at line 142 of file convert_pose_alg_node.h.

geometry_msgs::PoseStamped ConvertPoseAlgNode::marker_ [private]

Definition at line 83 of file convert_pose_alg_node.h.

Definition at line 82 of file convert_pose_alg_node.h.

Definition at line 80 of file convert_pose_alg_node.h.

Definition at line 105 of file convert_pose_alg_node.h.

Definition at line 106 of file convert_pose_alg_node.h.

Definition at line 121 of file convert_pose_alg_node.h.

Definition at line 122 of file convert_pose_alg_node.h.

Definition at line 113 of file convert_pose_alg_node.h.

Definition at line 114 of file convert_pose_alg_node.h.

ar_pose::ARMarkers ConvertPoseAlgNode::msg_ [private]

Definition at line 87 of file convert_pose_alg_node.h.

int ConvertPoseAlgNode::n [private]

Definition at line 147 of file convert_pose_alg_node.h.

Definition at line 140 of file convert_pose_alg_node.h.

Definition at line 141 of file convert_pose_alg_node.h.

Definition at line 130 of file convert_pose_alg_node.h.

Definition at line 137 of file convert_pose_alg_node.h.

Definition at line 119 of file convert_pose_alg_node.h.

Definition at line 134 of file convert_pose_alg_node.h.

Definition at line 133 of file convert_pose_alg_node.h.

Definition at line 139 of file convert_pose_alg_node.h.

geometry_msgs::PoseStamped ConvertPoseAlgNode::right_pose_ [private]

Definition at line 85 of file convert_pose_alg_node.h.

Definition at line 143 of file convert_pose_alg_node.h.

Definition at line 149 of file convert_pose_alg_node.h.

Definition at line 145 of file convert_pose_alg_node.h.

Definition at line 129 of file convert_pose_alg_node.h.

Definition at line 98 of file convert_pose_alg_node.h.

Definition at line 99 of file convert_pose_alg_node.h.

geometry_msgs::Twist ConvertPoseAlgNode::Twist_msg_ [private]

Definition at line 65 of file convert_pose_alg_node.h.


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


convert_pose
Author(s): darwin
autogenerated on Fri Dec 6 2013 20:54:52