Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
play_motion::ApproachPlanner Class Reference

TODO. More...

#include <approach_planner.h>

List of all members.

Classes

struct  PlanningData

Public Member Functions

 ApproachPlanner (const ros::NodeHandle &nh)
bool needsApproach (const std::vector< double > &current_pos, const std::vector< double > &goal_pos)
 TODO.
bool prependApproach (const std::vector< std::string > &joint_names, const std::vector< double > &current_pos, bool skip_planning, const std::vector< TrajPoint > &traj_in, std::vector< TrajPoint > &traj_out)
 TODO.

Private Types

typedef boost::shared_ptr
< ros::AsyncSpinner
AsyncSpinnerPtr
typedef boost::shared_ptr
< ros::CallbackQueue
CallbackQueuePtr
typedef std::map< std::string,
double > 
JointGoal
typedef std::vector< std::string > JointNames
typedef
moveit::planning_interface::MoveGroup 
MoveGroup
typedef boost::shared_ptr
< MoveGroup
MoveGroupPtr

Private Member Functions

void combineTrajectories (const JointNames &joint_names, const std::vector< double > &current_pos, const std::vector< TrajPoint > &traj_in, trajectory_msgs::JointTrajectory &approach, std::vector< TrajPoint > &traj_out)
 TODO.
bool computeApproach (const JointNames &joint_names, const std::vector< double > &current_pos, const std::vector< double > &goal_pos, trajectory_msgs::JointTrajectory &traj)
 TODO.
std::vector< MoveGroupPtrgetValidMoveGroups (const JointNames &min_group, const JointNames &max_group)
 TODO.
bool isPlanningJoint (const std::string &joint_name) const
 TODO.
double noPlanningReachTime (const std::vector< double > &curr_pos, const std::vector< double > &goal_pos)
 TODO.
bool planApproach (const JointNames &joint_names, const std::vector< double > &joint_values, MoveGroupPtr move_group, trajectory_msgs::JointTrajectory &traj)
 TODO.

Private Attributes

CallbackQueuePtr cb_queue_
double joint_tol_
 Absolute tolerance used to determine if two joint positions are approximately equal.
std::vector< std::string > no_plan_joints_
std::vector< PlanningDataplanning_data_
bool planning_disabled_
double skip_planning_min_dur_
 Minimum duration that a non-planned approach can have.
double skip_planning_vel_
 Maximum average velocity that any joint can have in a non-planned approach.
AsyncSpinnerPtr spinner_

Detailed Description

TODO.

Definition at line 72 of file approach_planner.h.


Member Typedef Documentation

Definition at line 92 of file approach_planner.h.

Definition at line 93 of file approach_planner.h.

typedef std::map<std::string, double> play_motion::ApproachPlanner::JointGoal [private]

Definition at line 95 of file approach_planner.h.

typedef std::vector<std::string> play_motion::ApproachPlanner::JointNames [private]

Definition at line 94 of file approach_planner.h.

Definition at line 90 of file approach_planner.h.

typedef boost::shared_ptr<MoveGroup> play_motion::ApproachPlanner::MoveGroupPtr [private]

Definition at line 91 of file approach_planner.h.


Constructor & Destructor Documentation

Definition at line 95 of file approach_planner.cpp.


Member Function Documentation

void play_motion::ApproachPlanner::combineTrajectories ( const JointNames joint_names,
const std::vector< double > &  current_pos,
const std::vector< TrajPoint > &  traj_in,
trajectory_msgs::JointTrajectory &  approach,
std::vector< TrajPoint > &  traj_out 
) [private]

TODO.

Definition at line 408 of file approach_planner.cpp.

bool play_motion::ApproachPlanner::computeApproach ( const JointNames joint_names,
const std::vector< double > &  current_pos,
const std::vector< double > &  goal_pos,
trajectory_msgs::JointTrajectory &  traj 
) [private]

TODO.

Definition at line 307 of file approach_planner.cpp.

vector< ApproachPlanner::MoveGroupPtr > play_motion::ApproachPlanner::getValidMoveGroups ( const JointNames min_group,
const JointNames max_group 
) [private]

TODO.

Definition at line 479 of file approach_planner.cpp.

bool play_motion::ApproachPlanner::isPlanningJoint ( const std::string &  joint_name) const [private]

TODO.

Definition at line 504 of file approach_planner.cpp.

bool play_motion::ApproachPlanner::needsApproach ( const std::vector< double > &  current_pos,
const std::vector< double > &  goal_pos 
)

TODO.

Definition at line 296 of file approach_planner.cpp.

double play_motion::ApproachPlanner::noPlanningReachTime ( const std::vector< double > &  curr_pos,
const std::vector< double > &  goal_pos 
) [private]

TODO.

Definition at line 509 of file approach_planner.cpp.

bool play_motion::ApproachPlanner::planApproach ( const JointNames joint_names,
const std::vector< double > &  joint_values,
MoveGroupPtr  move_group,
trajectory_msgs::JointTrajectory &  traj 
) [private]

TODO.

Definition at line 373 of file approach_planner.cpp.

bool play_motion::ApproachPlanner::prependApproach ( const std::vector< std::string > &  joint_names,
const std::vector< double > &  current_pos,
bool  skip_planning,
const std::vector< TrajPoint > &  traj_in,
std::vector< TrajPoint > &  traj_out 
)

TODO.

Definition at line 198 of file approach_planner.cpp.


Member Data Documentation

Definition at line 109 of file approach_planner.h.

Absolute tolerance used to determine if two joint positions are approximately equal.

Definition at line 106 of file approach_planner.h.

std::vector<std::string> play_motion::ApproachPlanner::no_plan_joints_ [private]

Definition at line 105 of file approach_planner.h.

Definition at line 104 of file approach_planner.h.

Definition at line 111 of file approach_planner.h.

Minimum duration that a non-planned approach can have.

Definition at line 108 of file approach_planner.h.

Maximum average velocity that any joint can have in a non-planned approach.

Definition at line 107 of file approach_planner.h.

Definition at line 110 of file approach_planner.h.


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


play_motion
Author(s): Paul Mathieu , Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Jun 8 2019 20:26:22