moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
38 
39 namespace chomp_interface
40 {
41 static const rclcpp::Logger LOGGER = rclcpp::get_logger("chomp_optimizer");
42 
43 CHOMPInterface::CHOMPInterface(const rclcpp::Node::SharedPtr& node) : ChompPlanner(), node_(node)
44 {
45  loadParams();
46 }
47 
49 {
50  node_->get_parameter_or("chomp.planning_time_limit", params_.planning_time_limit_, 10.0);
51  node_->get_parameter_or("chomp.max_iterations", params_.max_iterations_, 200);
52  node_->get_parameter_or("chomp.max_iterations_after_collision_free", params_.max_iterations_after_collision_free_, 5);
53 
54  node_->get_parameter_or("chomp.smoothness_cost_weight", params_.smoothness_cost_weight_, 0.1);
55  node_->get_parameter_or("chomp.obstacle_cost_weight", params_.obstacle_cost_weight_, 1.0);
56  node_->get_parameter_or("chomp.learning_rate", params_.learning_rate_, 0.01);
57 
58  node_->get_parameter_or("chomp.smoothness_cost_velocity", params_.smoothness_cost_velocity_, 0.0);
59  node_->get_parameter_or("chomp.smoothness_cost_acceleration", params_.smoothness_cost_acceleration_, 1.0);
60  node_->get_parameter_or("chomp.smoothness_cost_jerk", params_.smoothness_cost_jerk_, 0.0);
61  node_->get_parameter_or("chomp.ridge_factor", params_.ridge_factor_, 0.0);
62  node_->get_parameter_or("chomp.use_pseudo_inverse", params_.use_pseudo_inverse_, false);
63  node_->get_parameter_or("chomp.pseudo_inverse_ridge_factor", params_.pseudo_inverse_ridge_factor_, 1e-4);
64 
65  node_->get_parameter_or("chomp.joint_update_limit", params_.joint_update_limit_, 0.1);
66  node_->get_parameter_or("chomp.collision_clearance", params_.min_clearance_, 0.2);
67  node_->get_parameter_or("chomp.collision_threshold", params_.collision_threshold_, 0.07);
68  node_->get_parameter_or("chomp.use_stochastic_descent", params_.use_stochastic_descent_, true);
69  params_.trajectory_initialization_method_ = "quintic-spline";
70  std::string method;
71  if (node_->get_parameter("chomp.trajectory_initialization_method", method) &&
73  {
74  RCLCPP_ERROR(LOGGER,
75  "Attempted to set trajectory_initialization_method to invalid value '%s'. Using default '%s' "
76  "instead.",
77  method.c_str(), params_.trajectory_initialization_method_.c_str());
78  }
79  node_->get_parameter_or("chomp.enable_failure_recovery", params_.enable_failure_recovery_, false);
80  node_->get_parameter_or("chomp.max_recovery_attempts", params_.max_recovery_attempts_, 5);
81 }
82 } // 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.