|
| float | cbCost (const Astar::Vec &s, Astar::Vec &e, const Astar::Vec &v_goal, const Astar::Vec &v_start) |
| |
| float | cbCostEstim (const Astar::Vec &s, const Astar::Vec &e) |
| |
| void | cbJoint (const sensor_msgs::JointState::ConstPtr &msg) |
| |
| bool | cbProgress (const std::list< Astar::Vec > &path_grid) |
| |
| std::vector< Astar::Vec > & | cbSearch (const Astar::Vec &p, const Astar::Vec &s, const Astar::Vec &e) |
| |
| void | cbTrajectory (const trajectory_msgs::JointTrajectory::ConstPtr &msg) |
| |
| float | euclidCost (const Astar::Vec &v, const Astar::Vecf coef) |
| |
| float | euclidCost (const Astar::Vec &v) |
| |
| void | grid2Metric (const int t0, const int t1, float >0, float >1) |
| |
| void | grid2Metric (const Astar::Vec t, Astar::Vecf >) |
| |
| bool | makePlan (const Astar::Vecf sg, const Astar::Vecf eg, std::list< Astar::Vecf > &path) |
| |
| void | metric2Grid (int &t0, int &t1, const float gt0, const float gt1) |
| |
| void | metric2Grid (Astar::Vec &t, const Astar::Vecf gt) |
| |
| void | replan () |
| |
| planner2dofSerialJointsNode::planner2dofSerialJointsNode |
( |
const std::string |
group_name | ) |
|
|
inlineexplicit |
| void planner2dofSerialJointsNode::cbJoint |
( |
const sensor_msgs::JointState::ConstPtr & |
msg | ) |
|
|
inlineprivate |
| bool planner2dofSerialJointsNode::cbProgress |
( |
const std::list< Astar::Vec > & |
path_grid | ) |
|
|
inlineprivate |
| void planner2dofSerialJointsNode::cbTrajectory |
( |
const trajectory_msgs::JointTrajectory::ConstPtr & |
msg | ) |
|
|
inlineprivate |
| float planner2dofSerialJointsNode::euclidCost |
( |
const Astar::Vec & |
v | ) |
|
|
inlineprivate |
| void planner2dofSerialJointsNode::grid2Metric |
( |
const int |
t0, |
|
|
const int |
t1, |
|
|
float & |
gt0, |
|
|
float & |
gt1 |
|
) |
| |
|
inlineprivate |
| void planner2dofSerialJointsNode::metric2Grid |
( |
int & |
t0, |
|
|
int & |
t1, |
|
|
const float |
gt0, |
|
|
const float |
gt1 |
|
) |
| |
|
inlineprivate |
| void planner2dofSerialJointsNode::replan |
( |
| ) |
|
|
inlineprivate |
| Astar planner2dofSerialJointsNode::as_ |
|
private |
| float planner2dofSerialJointsNode::avg_vel_ |
|
private |
| Astar::Gridmap<char, 0x40> planner2dofSerialJointsNode::cm_ |
|
private |
| std::pair<ros::Duration, std::pair<float, float> > planner2dofSerialJointsNode::cmd_prev |
|
private |
| bool planner2dofSerialJointsNode::debug_aa_ |
|
private |
| Astar::Vecf planner2dofSerialJointsNode::euclid_cost_coef_ |
|
private |
| float planner2dofSerialJointsNode::expand_ |
|
private |
| float planner2dofSerialJointsNode::freq_ |
|
private |
| float planner2dofSerialJointsNode::freq_min_ |
|
private |
| std::string planner2dofSerialJointsNode::group_ |
|
private |
| bool planner2dofSerialJointsNode::has_goal_ |
|
private |
| bool planner2dofSerialJointsNode::has_start_ |
|
private |
| int planner2dofSerialJointsNode::id[2] |
|
private |
| sensor_msgs::JointState planner2dofSerialJointsNode::joint_ |
|
private |
| LinkBody planner2dofSerialJointsNode::links_[2] |
|
private |
| ros::Time planner2dofSerialJointsNode::replan_prev_ |
|
private |
| int planner2dofSerialJointsNode::resolution_ |
|
private |
| std::vector<Astar::Vec> planner2dofSerialJointsNode::search_list_ |
|
private |
| planner_cspace_msgs::PlannerStatus planner2dofSerialJointsNode::status_ |
|
private |
| trajectory_msgs::JointTrajectory planner2dofSerialJointsNode::traj_prev |
|
private |
| float planner2dofSerialJointsNode::weight_cost_ |
|
private |
The documentation for this class was generated from the following file: