move_arm::MoveArm Class Reference

List of all members.

Public Member Functions

bool configure ()
 MoveArm (const std::string &group_name)
virtual ~MoveArm ()

Private Member Functions

void addCheckFlags (planning_environment_msgs::GetStateValidity::Request &req, const int &flag)
bool checkIK (const geometry_msgs::PoseStamped &pose_stamped_msg, const std::string &link_name, sensor_msgs::JointState &solution)
bool checkJointGoal (motion_planning_msgs::GetMotionPlan::Request &req, motion_planning_msgs::ArmNavigationErrorCodes &error_code)
 Check the joint goal if it is valid.
bool checkTrajectoryReachesGoal (const trajectory_msgs::JointTrajectory &joint_traj, motion_planning_msgs::ArmNavigationErrorCodes &error_code)
 Checks if the last state in a trajectory actually reaches the desired point.
int closestStateOnTrajectory (const trajectory_msgs::JointTrajectory &trajectory, const sensor_msgs::JointState &joint_state, unsigned int start, unsigned int end)
bool computeIK (const geometry_msgs::PoseStamped &pose_stamped_msg, const std::string &link_name, sensor_msgs::JointState &solution)
void controllerTransitionCallback (JointExecutorActionClient::GoalHandle gh)
bool convertPoseGoalToJointGoal (motion_planning_msgs::GetMotionPlan::Request &req)
bool createPlan (motion_planning_msgs::GetMotionPlan::Request &req, motion_planning_msgs::GetMotionPlan::Response &res)
void discretizeTrajectory (const trajectory_msgs::JointTrajectory &trajectory, trajectory_msgs::JointTrajectory &trajectory_out, const double &trajectory_discretization)
bool doPrePlanningChecks (motion_planning_msgs::GetMotionPlan::Request &req, motion_planning_msgs::GetMotionPlan::Response &res)
void execute (const move_arm_msgs::MoveArmGoalConstPtr &goal)
bool executeCycle (motion_planning_msgs::GetMotionPlan::Request &req)
void fillTrajectoryMsg (const trajectory_msgs::JointTrajectory &trajectory_in, trajectory_msgs::JointTrajectory &trajectory_out)
bool filterTrajectory (const trajectory_msgs::JointTrajectory &trajectory_in, trajectory_msgs::JointTrajectory &trajectory_out)
bool getRobotState (motion_planning_msgs::RobotState &robot_state)
bool initializeControllerInterface ()
bool isControllerDone (motion_planning_msgs::ArmNavigationErrorCodes &error_code)
bool isEnvironmentSafe ()
bool isExecutionSafe ()
bool isJointGoal (motion_planning_msgs::GetMotionPlan::Request &req)
bool isPoseGoal (motion_planning_msgs::GetMotionPlan::Request &req)
bool isStateValid (const motion_planning_msgs::RobotState &state, motion_planning_msgs::ArmNavigationErrorCodes &error_code, int flag=0)
bool isStateValidAtGoal (const motion_planning_msgs::RobotState &state, motion_planning_msgs::ArmNavigationErrorCodes &error_code)
bool isTrajectoryValid (const trajectory_msgs::JointTrajectory &traj, motion_planning_msgs::ArmNavigationErrorCodes &error_code)
void moveArmGoalToPlannerRequest (const move_arm_msgs::MoveArmGoalConstPtr &goal, motion_planning_msgs::GetMotionPlan::Request &req)
void printTrajectory (const trajectory_msgs::JointTrajectory &trajectory)
void publishStats ()
bool removeCompletedTrajectory (const trajectory_msgs::JointTrajectory &trajectory_in, trajectory_msgs::JointTrajectory &trajectory_out, bool zero_vel_acc)
void resetStateMachine ()
bool sendTrajectory (trajectory_msgs::JointTrajectory &current_trajectory)
void stopMonitoring ()
bool stopTrajectory ()
void visualizeAllowedContactRegions (const std::vector< motion_planning_msgs::AllowedContactSpecification > &allowed_contacts)
void visualizeJointGoal (const trajectory_msgs::JointTrajectory &trajectory)
void visualizeJointGoal (motion_planning_msgs::GetMotionPlan::Request &req)
void visualizePlan (const trajectory_msgs::JointTrajectory &trajectory)

Private Attributes

boost::shared_ptr
< actionlib::SimpleActionServer
< move_arm_msgs::MoveArmAction > > 
action_server_
std::vector< std::string > all_link_names_
ros::Publisher allowed_contact_regions_publisher_
bool arm_ik_initialized_
ros::ServiceClient check_env_safe_client_
ros::ServiceClient check_execution_safe_client_
ros::ServiceClient check_plan_validity_client_
ros::ServiceClient check_state_at_goal_client_
ros::ServiceClient check_state_validity_client_
JointExecutorActionClientcontroller_action_client_
JointExecutorActionClient::GoalHandle controller_goal_handle_
ControllerStatus controller_status_
trajectory_msgs::JointTrajectory current_trajectory_
ros::Publisher display_joint_goal_publisher_
ros::Publisher display_path_publisher_
ros::ServiceClient filter_trajectory_client_
ros::ServiceClient fk_client_
ros::ServiceClient get_group_info_client_
ros::ServiceClient get_state_client_
std::string group_
std::vector< std::string > group_joint_names_
std::vector< std::string > group_link_names_
boost::shared_ptr
< actionlib::SimpleActionClient
< move_arm_head_monitor::HeadLookAction > > 
head_look_client_
boost::shared_ptr
< actionlib::SimpleActionClient
< move_arm_head_monitor::HeadMonitorAction > > 
head_monitor_client_
std::string head_monitor_link_
double head_monitor_link_x_
double head_monitor_link_y_
double head_monitor_link_z_
double head_monitor_max_frequency_
double head_monitor_time_offset_
double ik_allowed_time_
ros::ServiceClient ik_client_
ros::Time last_monitor_time_
move_arm_msgs::MoveArmFeedback move_arm_action_feedback_
move_arm_msgs::MoveArmResult move_arm_action_result_
double move_arm_frequency_
MoveArmParameters move_arm_parameters_
move_arm_msgs::MoveArmStatistics move_arm_stats_
int num_planning_attempts_
motion_planning_msgs::GetMotionPlan::Request original_request_
double pause_allowed_time_
ros::Time pause_start_time_
ros::NodeHandle private_handle_
bool publish_stats_
urdf::Model robot_model_
 A model of the robot to see which joints wrap around.
bool robot_model_initialized_
 Flag that tells us if the robot model was initialized successfully.
ros::NodeHandle root_handle_
MoveArmState state_
ros::Publisher stats_publisher_
tf::TransformListener * tf_
ros::ServiceClient trajectory_cancel_client_
double trajectory_discretization_
double trajectory_filter_allowed_time_
ros::Duration trajectory_monitoring_duration_
ros::ServiceClient trajectory_query_client_
ros::ServiceClient trajectory_start_client_
bool using_head_monitor_

Detailed Description

Definition at line 137 of file move_arm_simple_action.cpp.


Constructor & Destructor Documentation

move_arm::MoveArm::MoveArm ( const std::string &  group_name  )  [inline]

Definition at line 141 of file move_arm_simple_action.cpp.

virtual move_arm::MoveArm::~MoveArm (  )  [inline, virtual]

Definition at line 255 of file move_arm_simple_action.cpp.


Member Function Documentation

void move_arm::MoveArm::addCheckFlags ( planning_environment_msgs::GetStateValidity::Request &  req,
const int &  flag 
) [inline, private]

Definition at line 925 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::checkIK ( const geometry_msgs::PoseStamped &  pose_stamped_msg,
const std::string &  link_name,
sensor_msgs::JointState &  solution 
) [inline, private]

Definition at line 434 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::checkJointGoal ( motion_planning_msgs::GetMotionPlan::Request &  req,
motion_planning_msgs::ArmNavigationErrorCodes &  error_code 
) [inline, private]

Check the joint goal if it is valid.

End Trajectory Filtering State and trajectory validity checks

Definition at line 655 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::checkTrajectoryReachesGoal ( const trajectory_msgs::JointTrajectory &  joint_traj,
motion_planning_msgs::ArmNavigationErrorCodes &  error_code 
) [inline, private]

Checks if the last state in a trajectory actually reaches the desired point.

Definition at line 680 of file move_arm_simple_action.cpp.

int move_arm::MoveArm::closestStateOnTrajectory ( const trajectory_msgs::JointTrajectory &  trajectory,
const sensor_msgs::JointState &  joint_state,
unsigned int  start,
unsigned int  end 
) [inline, private]

Definition at line 511 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::computeIK ( const geometry_msgs::PoseStamped &  pose_stamped_msg,
const std::string &  link_name,
sensor_msgs::JointState &  solution 
) [inline, private]

Definition at line 391 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::configure ( void   )  [inline]

Definition at line 259 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::controllerTransitionCallback ( JointExecutorActionClient::GoalHandle  gh  )  [inline, private]

Definition at line 1161 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::convertPoseGoalToJointGoal ( motion_planning_msgs::GetMotionPlan::Request &  req  )  [inline, private]

Kinematics

Definition at line 312 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::createPlan ( motion_planning_msgs::GetMotionPlan::Request &  req,
motion_planning_msgs::GetMotionPlan::Response &  res 
) [inline, private]

Definition at line 1031 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::discretizeTrajectory ( const trajectory_msgs::JointTrajectory &  trajectory,
trajectory_msgs::JointTrajectory &  trajectory_out,
const double &  trajectory_discretization 
) [inline, private]

Definition at line 868 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::doPrePlanningChecks ( motion_planning_msgs::GetMotionPlan::Request &  req,
motion_planning_msgs::GetMotionPlan::Response &  res 
) [inline, private]

Definition at line 983 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::execute ( const move_arm_msgs::MoveArmGoalConstPtr &  goal  )  [inline, private]

Definition at line 1584 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::executeCycle ( motion_planning_msgs::GetMotionPlan::Request &  req  )  [inline, private]

Definition at line 1307 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::fillTrajectoryMsg ( const trajectory_msgs::JointTrajectory &  trajectory_in,
trajectory_msgs::JointTrajectory &  trajectory_out 
) [inline, private]

Definition at line 1220 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::filterTrajectory ( const trajectory_msgs::JointTrajectory &  trajectory_in,
trajectory_msgs::JointTrajectory &  trajectory_out 
) [inline, private]

End Kinematics Trajectory Filtering

Definition at line 477 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::getRobotState ( motion_planning_msgs::RobotState &  robot_state  )  [inline, private]

Definition at line 937 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::initializeControllerInterface (  )  [inline, private]

End Motion planning Control

Definition at line 1082 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::isControllerDone ( motion_planning_msgs::ArmNavigationErrorCodes &  error_code  )  [inline, private]

Definition at line 1206 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::isEnvironmentSafe (  )  [inline, private]

Definition at line 700 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::isExecutionSafe (  )  [inline, private]

Definition at line 761 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::isJointGoal ( motion_planning_msgs::GetMotionPlan::Request &  req  )  [inline, private]

Definition at line 916 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::isPoseGoal ( motion_planning_msgs::GetMotionPlan::Request &  req  )  [inline, private]

State and trajectory validity checks Helper functions

Definition at line 907 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::isStateValid ( const motion_planning_msgs::RobotState &  state,
motion_planning_msgs::ArmNavigationErrorCodes &  error_code,
int  flag = 0 
) [inline, private]

Definition at line 828 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::isStateValidAtGoal ( const motion_planning_msgs::RobotState &  state,
motion_planning_msgs::ArmNavigationErrorCodes &  error_code 
) [inline, private]

Definition at line 795 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::isTrajectoryValid ( const trajectory_msgs::JointTrajectory &  traj,
motion_planning_msgs::ArmNavigationErrorCodes &  error_code 
) [inline, private]

Definition at line 717 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::moveArmGoalToPlannerRequest ( const move_arm_msgs::MoveArmGoalConstPtr &  goal,
motion_planning_msgs::GetMotionPlan::Request &  req 
) [inline, private]

End Helper Functions Motion planning

Definition at line 960 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::printTrajectory ( const trajectory_msgs::JointTrajectory &  trajectory  )  [inline, private]

Definition at line 1675 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::publishStats (  )  [inline, private]

End State machine Visualization and I/O

Definition at line 1656 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::removeCompletedTrajectory ( const trajectory_msgs::JointTrajectory &  trajectory_in,
trajectory_msgs::JointTrajectory &  trajectory_out,
bool  zero_vel_acc 
) [inline, private]

Definition at line 570 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::resetStateMachine (  )  [inline, private]

End Control State machine

Definition at line 1300 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::sendTrajectory ( trajectory_msgs::JointTrajectory &  current_trajectory  )  [inline, private]

Definition at line 1121 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::stopMonitoring (  )  [inline, private]

Definition at line 1102 of file move_arm_simple_action.cpp.

bool move_arm::MoveArm::stopTrajectory (  )  [inline, private]

Definition at line 1111 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::visualizeAllowedContactRegions ( const std::vector< motion_planning_msgs::AllowedContactSpecification > &  allowed_contacts  )  [inline, private]

Definition at line 1735 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::visualizeJointGoal ( const trajectory_msgs::JointTrajectory &  trajectory  )  [inline, private]

Definition at line 1707 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::visualizeJointGoal ( motion_planning_msgs::GetMotionPlan::Request &  req  )  [inline, private]

Definition at line 1686 of file move_arm_simple_action.cpp.

void move_arm::MoveArm::visualizePlan ( const trajectory_msgs::JointTrajectory &  trajectory  )  [inline, private]

Definition at line 1722 of file move_arm_simple_action.cpp.


Member Data Documentation

boost::shared_ptr<actionlib::SimpleActionServer<move_arm_msgs::MoveArmAction> > move_arm::MoveArm::action_server_ [private]

Definition at line 1822 of file move_arm_simple_action.cpp.

std::vector<std::string> move_arm::MoveArm::all_link_names_ [private]

Definition at line 1835 of file move_arm_simple_action.cpp.

Definition at line 1848 of file move_arm_simple_action.cpp.

Definition at line 1859 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::check_env_safe_client_ [private]

Definition at line 1819 of file move_arm_simple_action.cpp.

Definition at line 1819 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::check_plan_validity_client_ [private]

Definition at line 1818 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::check_state_at_goal_client_ [private]

Definition at line 1818 of file move_arm_simple_action.cpp.

Definition at line 1819 of file move_arm_simple_action.cpp.

Definition at line 1854 of file move_arm_simple_action.cpp.

JointExecutorActionClient::GoalHandle move_arm::MoveArm::controller_goal_handle_ [private]

Definition at line 1855 of file move_arm_simple_action.cpp.

Definition at line 1852 of file move_arm_simple_action.cpp.

trajectory_msgs::JointTrajectory move_arm::MoveArm::current_trajectory_ [private]

Definition at line 1829 of file move_arm_simple_action.cpp.

Definition at line 1847 of file move_arm_simple_action.cpp.

Definition at line 1846 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::filter_trajectory_client_ [private]

Definition at line 1849 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::fk_client_ [private]

Definition at line 1850 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::get_group_info_client_ [private]

Definition at line 1817 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::get_state_client_ [private]

Definition at line 1817 of file move_arm_simple_action.cpp.

std::string move_arm::MoveArm::group_ [private]

End Visualization and I/O

Definition at line 1812 of file move_arm_simple_action.cpp.

std::vector<std::string> move_arm::MoveArm::group_joint_names_ [private]

Definition at line 1833 of file move_arm_simple_action.cpp.

std::vector<std::string> move_arm::MoveArm::group_link_names_ [private]

Definition at line 1834 of file move_arm_simple_action.cpp.

boost::shared_ptr<actionlib::SimpleActionClient<move_arm_head_monitor::HeadLookAction> > move_arm::MoveArm::head_look_client_ [private]

Definition at line 1815 of file move_arm_simple_action.cpp.

boost::shared_ptr<actionlib::SimpleActionClient<move_arm_head_monitor::HeadMonitorAction> > move_arm::MoveArm::head_monitor_client_ [private]

Definition at line 1814 of file move_arm_simple_action.cpp.

Definition at line 1861 of file move_arm_simple_action.cpp.

Definition at line 1862 of file move_arm_simple_action.cpp.

Definition at line 1862 of file move_arm_simple_action.cpp.

Definition at line 1862 of file move_arm_simple_action.cpp.

Definition at line 1862 of file move_arm_simple_action.cpp.

Definition at line 1862 of file move_arm_simple_action.cpp.

Definition at line 1857 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::ik_client_ [private]

Definition at line 1818 of file move_arm_simple_action.cpp.

Definition at line 1828 of file move_arm_simple_action.cpp.

move_arm_msgs::MoveArmFeedback move_arm::MoveArm::move_arm_action_feedback_ [private]

Definition at line 1837 of file move_arm_simple_action.cpp.

move_arm_msgs::MoveArmResult move_arm::MoveArm::move_arm_action_result_ [private]

Definition at line 1836 of file move_arm_simple_action.cpp.

Definition at line 1826 of file move_arm_simple_action.cpp.

Definition at line 1851 of file move_arm_simple_action.cpp.

move_arm_msgs::MoveArmStatistics move_arm::MoveArm::move_arm_stats_ [private]

Definition at line 1868 of file move_arm_simple_action.cpp.

Definition at line 1831 of file move_arm_simple_action.cpp.

motion_planning_msgs::GetMotionPlan::Request move_arm::MoveArm::original_request_ [private]

Definition at line 1839 of file move_arm_simple_action.cpp.

Definition at line 1863 of file move_arm_simple_action.cpp.

Definition at line 1864 of file move_arm_simple_action.cpp.

ros::NodeHandle move_arm::MoveArm::private_handle_ [private]

Definition at line 1821 of file move_arm_simple_action.cpp.

Definition at line 1867 of file move_arm_simple_action.cpp.

urdf::Model move_arm::MoveArm::robot_model_ [private]

A model of the robot to see which joints wrap around.

Definition at line 1842 of file move_arm_simple_action.cpp.

Flag that tells us if the robot model was initialized successfully.

Definition at line 1844 of file move_arm_simple_action.cpp.

ros::NodeHandle move_arm::MoveArm::root_handle_ [private]

Definition at line 1821 of file move_arm_simple_action.cpp.

Definition at line 1825 of file move_arm_simple_action.cpp.

ros::Publisher move_arm::MoveArm::stats_publisher_ [private]

Definition at line 1869 of file move_arm_simple_action.cpp.

tf::TransformListener* move_arm::MoveArm::tf_ [private]

Definition at line 1824 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::trajectory_cancel_client_ [private]

Definition at line 1820 of file move_arm_simple_action.cpp.

Definition at line 1858 of file move_arm_simple_action.cpp.

Definition at line 1857 of file move_arm_simple_action.cpp.

Definition at line 1827 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::trajectory_query_client_ [private]

Definition at line 1820 of file move_arm_simple_action.cpp.

ros::ServiceClient move_arm::MoveArm::trajectory_start_client_ [private]

Definition at line 1820 of file move_arm_simple_action.cpp.

Definition at line 1865 of file move_arm_simple_action.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


move_arm
Author(s): Ioan Sucan, Sachin Chitta(sachinc@willowgarage.com)
autogenerated on Fri Jan 11 10:05:23 2013