#include <robot_model_plugin.h>
Public Types | |
typedef boost::shared_ptr < const RobotModelPlugin > | ConstPtr |
typedef boost::shared_ptr < RobotModelPlugin > | Ptr |
Public Member Functions | |
const geometry_msgs::Vector3 & | getFootSize () const |
const geometry_msgs::Vector3 & | getUpperBodyOriginShift () const |
const geometry_msgs::Vector3 & | getUpperBodySize () const |
bool | initialize (const vigir_generic_params::ParameterSet ¶ms=vigir_generic_params::ParameterSet()) override |
bool | isUnique () const final |
virtual void | reset () |
Resets the plugin to initial state. | |
RobotModelPlugin () | |
Protected Attributes | |
geometry_msgs::Vector3 | foot_size_ |
geometry_msgs::Vector3 | upper_body_origin_shift_ |
geometry_msgs::Vector3 | upper_body_size_ |
Definition at line 42 of file robot_model_plugin.h.
typedef boost::shared_ptr<const RobotModelPlugin> vigir_footstep_planning::RobotModelPlugin::ConstPtr |
Definition at line 48 of file robot_model_plugin.h.
typedef boost::shared_ptr<RobotModelPlugin> vigir_footstep_planning::RobotModelPlugin::Ptr |
Definition at line 47 of file robot_model_plugin.h.
Definition at line 9 of file robot_model_plugin.cpp.
const geometry_msgs::Vector3 & vigir_footstep_planning::RobotModelPlugin::getFootSize | ( | ) | const |
Definition at line 34 of file robot_model_plugin.cpp.
const geometry_msgs::Vector3 & vigir_footstep_planning::RobotModelPlugin::getUpperBodyOriginShift | ( | ) | const |
Definition at line 44 of file robot_model_plugin.cpp.
const geometry_msgs::Vector3 & vigir_footstep_planning::RobotModelPlugin::getUpperBodySize | ( | ) | const |
Definition at line 39 of file robot_model_plugin.cpp.
bool vigir_footstep_planning::RobotModelPlugin::initialize | ( | const vigir_generic_params::ParameterSet & | params = vigir_generic_params::ParameterSet() | ) | [override] |
Definition at line 14 of file robot_model_plugin.cpp.
bool vigir_footstep_planning::RobotModelPlugin::isUnique | ( | ) | const |
Definition at line 29 of file robot_model_plugin.cpp.
virtual void vigir_footstep_planning::RobotModelPlugin::reset | ( | ) | [inline, virtual] |
Resets the plugin to initial state.
Definition at line 57 of file robot_model_plugin.h.
Definition at line 67 of file robot_model_plugin.h.
geometry_msgs::Vector3 vigir_footstep_planning::RobotModelPlugin::upper_body_origin_shift_ [protected] |
Definition at line 71 of file robot_model_plugin.h.
Definition at line 70 of file robot_model_plugin.h.