41 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"chomp_optimizer");
71 if (
node_->get_parameter(
"chomp.trajectory_initialization_method", method) &&
75 "Attempted to set trajectory_initialization_method to invalid value '%s'. Using default '%s' "
double collision_threshold_
double planning_time_limit_
std::string trajectory_initialization_method_
double smoothness_cost_weight_
int max_recovery_attempts_
double smoothness_cost_jerk_
double smoothness_cost_acceleration_
bool use_stochastic_descent_
double pseudo_inverse_ridge_factor_
bool enable_failure_recovery_
double smoothness_cost_velocity_
int max_iterations_after_collision_free_
double joint_update_limit_
bool setTrajectoryInitializationMethod(std::string method)
double obstacle_cost_weight_
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.