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 CHOMPInterface::CHOMPInterface(const ros::NodeHandle& nh) : ChompPlanner(), nh_(nh)
42 {
43  loadParams();
44 }
45 
47 {
48  nh_.param("planning_time_limit", params_.planning_time_limit_, 10.0);
49  nh_.param("max_iterations", params_.max_iterations_, 200);
50  nh_.param("max_iterations_after_collision_free", params_.max_iterations_after_collision_free_, 5);
51  nh_.param("smoothness_cost_weight", params_.smoothness_cost_weight_, 0.1);
52  nh_.param("obstacle_cost_weight", params_.obstacle_cost_weight_, 1.0);
53  nh_.param("learning_rate", params_.learning_rate_, 0.01);
54 
55  // nh_.param("add_randomness", params_.add_randomness_, false);
56  nh_.param("smoothness_cost_velocity", params_.smoothness_cost_velocity_, 0.0);
57  nh_.param("smoothness_cost_acceleration", params_.smoothness_cost_acceleration_, 1.0);
58  nh_.param("smoothness_cost_jerk", params_.smoothness_cost_jerk_, 0.0);
59  // nh_.param("hmc_discretization", params_.hmc_discretization_, 0.01);
60  // nh_.param("hmc_stochasticity", params_.hmc_stochasticity_, 0.01);
61  // nh_.param("hmc_annealing_factor", params_.hmc_annealing_factor_, 0.99);
62  // nh_.param("use_hamiltonian_monte_carlo", params_.use_hamiltonian_monte_carlo_, false);
63  nh_.param("ridge_factor", params_.ridge_factor_, 0.0);
64  nh_.param("use_pseudo_inverse", params_.use_pseudo_inverse_, false);
65  nh_.param("pseudo_inverse_ridge_factor", params_.pseudo_inverse_ridge_factor_, 1e-4);
66 
67  nh_.param("joint_update_limit", params_.joint_update_limit_, 0.1);
68  nh_.param("collision_clearence", params_.min_clearence_, 0.2);
69  nh_.param("collision_threshold", params_.collision_threshold_, 0.07);
70  // nh_.param("random_jump_amount", params_.random_jump_amount_, 1.0);
71  nh_.param("use_stochastic_descent", params_.use_stochastic_descent_, true);
72  nh_.param("trajectory_initialization_method", params_.trajectory_initialization_method_,
73  std::string("quintic-spline"));
74  nh_.param("enable_failure_recovery", params_.enable_failure_recovery_, false);
75  nh_.param("max_recovery_attempts", params_.max_recovery_attempts_, 5);
76 }
77 }
std::string trajectory_initialization_method_
chomp::ChompParameters params_
The ROS node handle.
double pseudo_inverse_ridge_factor_
double smoothness_cost_acceleration_
void loadParams()
Configure everything using the param server.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
CHOMPInterface(const ros::NodeHandle &nh=ros::NodeHandle("~"))
int max_iterations_after_collision_free_


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