moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
chomp_interface.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: E. Gil Jones */
36
39
40namespace chomp_interface
41{
42namespace
43{
44rclcpp::Logger getLogger()
45{
46 return moveit::getLogger("moveit.planners.chomp");
47}
48} // namespace
49
50CHOMPInterface::CHOMPInterface(const rclcpp::Node::SharedPtr& node) : ChompPlanner(), node_(node)
51{
52 loadParams();
53}
54
56{
57 node_->get_parameter_or("chomp.planning_time_limit", params_.planning_time_limit_, 10.0);
58 node_->get_parameter_or("chomp.max_iterations", params_.max_iterations_, 200);
59 node_->get_parameter_or("chomp.max_iterations_after_collision_free", params_.max_iterations_after_collision_free_, 5);
60
61 node_->get_parameter_or("chomp.smoothness_cost_weight", params_.smoothness_cost_weight_, 0.1);
62 node_->get_parameter_or("chomp.obstacle_cost_weight", params_.obstacle_cost_weight_, 1.0);
63 node_->get_parameter_or("chomp.learning_rate", params_.learning_rate_, 0.01);
64
65 node_->get_parameter_or("chomp.smoothness_cost_velocity", params_.smoothness_cost_velocity_, 0.0);
66 node_->get_parameter_or("chomp.smoothness_cost_acceleration", params_.smoothness_cost_acceleration_, 1.0);
67 node_->get_parameter_or("chomp.smoothness_cost_jerk", params_.smoothness_cost_jerk_, 0.0);
68 node_->get_parameter_or("chomp.ridge_factor", params_.ridge_factor_, 0.0);
69 node_->get_parameter_or("chomp.use_pseudo_inverse", params_.use_pseudo_inverse_, false);
70 node_->get_parameter_or("chomp.pseudo_inverse_ridge_factor", params_.pseudo_inverse_ridge_factor_, 1e-4);
71
72 node_->get_parameter_or("chomp.joint_update_limit", params_.joint_update_limit_, 0.1);
73 node_->get_parameter_or("chomp.collision_clearance", params_.min_clearance_, 0.2);
74 node_->get_parameter_or("chomp.collision_threshold", params_.collision_threshold_, 0.07);
75 node_->get_parameter_or("chomp.use_stochastic_descent", params_.use_stochastic_descent_, true);
77 std::string method;
78 if (node_->get_parameter("chomp.trajectory_initialization_method", method) &&
80 {
81 RCLCPP_ERROR(getLogger(),
82 "Attempted to set trajectory_initialization_method to invalid value '%s'. Using default '%s' "
83 "instead.",
84 method.c_str(), params_.trajectory_initialization_method_.c_str());
85 }
86 node_->get_parameter_or("chomp.enable_failure_recovery", params_.enable_failure_recovery_, false);
87 node_->get_parameter_or("chomp.max_recovery_attempts", params_.max_recovery_attempts_, 5);
88}
89} // namespace chomp_interface
std::string trajectory_initialization_method_
bool setTrajectoryInitializationMethod(std::string method)
chomp::ChompParameters params_
The ROS node.
std::shared_ptr< rclcpp::Node > node_
CHOMPInterface(const rclcpp::Node::SharedPtr &node)
void loadParams()
Configure everything using the param server.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79