chomp_planning_context.cpp
Go to the documentation of this file.
1 /*
2  * chomp_planning_context.cpp
3  *
4  * Created on: 27-Jul-2016
5  * Author: ace
6  */
7 
11 
12 namespace chomp_interface
13 {
14 CHOMPPlanningContext::CHOMPPlanningContext(const std::string& name, const std::string& group,
15  const robot_model::RobotModelConstPtr& model)
16  : planning_interface::PlanningContext(name, group), robot_model_(model)
17 {
18  chomp_interface_ = CHOMPInterfacePtr(new CHOMPInterface());
19 }
20 
22 {
23 }
24 
26 {
27  moveit_msgs::MotionPlanDetailedResponse res2;
28  if (chomp_interface_->solve(planning_scene_, request_, chomp_interface_->getParams(), res2))
29  {
30  res.trajectory_.resize(1);
31  res.trajectory_[0] =
32  robot_trajectory::RobotTrajectoryPtr(new robot_trajectory::RobotTrajectory(robot_model_, getGroupName()));
33 
35  robot_state::robotStateMsgToRobotState(res2.trajectory_start, start_state);
36  res.trajectory_[0]->setRobotTrajectoryMsg(start_state, res2.trajectory[0]);
37 
39  itp.computeTimeStamps(*res.trajectory_[0], request_.max_velocity_scaling_factor,
40  request_.max_acceleration_scaling_factor);
41 
42  res.description_.push_back("plan");
43  res.processing_time_ = res2.processing_time;
44  res.error_code_ = res2.error_code;
45  return true;
46  }
47  else
48  {
49  res.error_code_ = res2.error_code;
50  return false;
51  }
52 }
53 
55 {
57  bool planning_success = solve(res_detailed);
58 
59  res.error_code_ = res_detailed.error_code_;
60 
61  if (planning_success)
62  {
63  res.trajectory_ = res_detailed.trajectory_[0];
64  res.planning_time_ = res_detailed.processing_time_[0];
65  }
66 
67  return planning_success;
68 }
69 
71 {
72  // TODO - make interruptible
73  return true;
74 }
75 
77 {
78 }
79 
80 } /* namespace chomp_interface */
CHOMPPlanningContext(const std::string &name, const std::string &group, const robot_model::RobotModelConstPtr &model)
robot_trajectory::RobotTrajectoryPtr trajectory_
moveit::core::RobotModelConstPtr robot_model_
moveit_msgs::MoveItErrorCodes error_code_
virtual bool solve(planning_interface::MotionPlanResponse &res)
planning_scene::PlanningSceneConstPtr planning_scene_
moveit_msgs::MoveItErrorCodes error_code_
const std::string & getGroupName() const
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const


chomp_interface
Author(s): Gil Jones
autogenerated on Wed Jul 10 2019 04:04:17