|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <chomp_interface.hpp>


Public Member Functions | |
| CHOMPInterface (const rclcpp::Node::SharedPtr &node) | |
| const chomp::ChompParameters & | getParams () const |
Public Member Functions inherited from chomp::ChompPlanner | |
| ChompPlanner ()=default | |
| virtual | ~ChompPlanner ()=default |
| void | solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, const ChompParameters ¶ms, planning_interface::MotionPlanDetailedResponse &res) const |
Protected Member Functions | |
| void | loadParams () |
| Configure everything using the param server. | |
Protected Attributes | |
| std::shared_ptr< rclcpp::Node > | node_ |
| chomp::ChompParameters | params_ |
| The ROS node. | |
Definition at line 48 of file chomp_interface.hpp.
| chomp_interface::CHOMPInterface::CHOMPInterface | ( | const rclcpp::Node::SharedPtr & | node | ) |
|
inline |
Definition at line 53 of file chomp_interface.hpp.
|
protected |
Configure everything using the param server.
Definition at line 55 of file chomp_interface.cpp.


|
protected |
Definition at line 62 of file chomp_interface.hpp.
|
protected |
The ROS node.
Definition at line 64 of file chomp_interface.hpp.