src
chomp_planning_context.cpp
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2012, Willow Garage, Inc.
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of Willow Garage nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*********************************************************************/
34
35
/* Author: Chittaranjan Srinivas Swaminathan */
36
37
#include <memory>
38
#include <
chomp_interface/chomp_planning_context.h
>
39
#include <
moveit/trajectory_processing/iterative_time_parameterization.h
>
40
#include <
moveit/robot_state/conversions.h
>
41
42
namespace
chomp_interface
43
{
44
CHOMPPlanningContext::CHOMPPlanningContext
(
const
std::string& name,
const
std::string& group,
45
const
moveit::core::RobotModelConstPtr& model,
ros::NodeHandle
& nh)
46
:
planning_interface
::PlanningContext(
name
, group), robot_model_(model)
47
{
48
chomp_interface_ = std::make_shared<CHOMPInterface>(nh);
49
}
50
51
bool
CHOMPPlanningContext::solve(
planning_interface::MotionPlanDetailedResponse
& res)
52
{
53
return
chomp_interface_->solve(planning_scene_, request_, chomp_interface_->getParams(), res);
54
}
55
56
bool
CHOMPPlanningContext::solve(
planning_interface::MotionPlanResponse
& res)
57
{
58
planning_interface::MotionPlanDetailedResponse
res_detailed;
59
bool
planning_success = solve(res_detailed);
60
61
res.
error_code_
= res_detailed.
error_code_
;
62
63
if
(planning_success)
64
{
65
res.
trajectory_
= res_detailed.
trajectory_
[0];
66
res.
planning_time_
= res_detailed.
processing_time_
[0];
67
}
68
69
return
planning_success;
70
}
71
72
bool
CHOMPPlanningContext::terminate()
73
{
74
// TODO - make interruptible
75
return
true
;
76
}
77
78
void
CHOMPPlanningContext::clear()
79
{
80
}
81
82
}
/* namespace chomp_interface */
planning_interface::MotionPlanResponse
chomp_interface
Definition:
chomp_interface.h:43
planning_interface::MotionPlanResponse::error_code_
moveit::core::MoveItErrorCode error_code_
name
std::string name
planning_interface::MotionPlanResponse::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
planning_interface::MotionPlanDetailedResponse::trajectory_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
chomp_interface::CHOMPPlanningContext::CHOMPPlanningContext
CHOMPPlanningContext(const std::string &name, const std::string &group, const moveit::core::RobotModelConstPtr &model, ros::NodeHandle &nh)
Definition:
chomp_planning_context.cpp:76
iterative_time_parameterization.h
planning_interface
planning_interface::MotionPlanDetailedResponse::error_code_
moveit::core::MoveItErrorCode error_code_
conversions.h
planning_interface::MotionPlanResponse::planning_time_
double planning_time_
chomp_planning_context.h
ros::NodeHandle
planning_interface::MotionPlanDetailedResponse
planning_interface::MotionPlanDetailedResponse::processing_time_
std::vector< double > processing_time_
chomp_interface
Author(s): Gil Jones
autogenerated on Sat May 3 2025 02:27:34