robot_model_plugin.cpp
Go to the documentation of this file.
2 
3 
4 
6 {
7 using namespace vigir_generic_params;
8 
10  : Plugin("robot_model")
11 {
12 }
13 
14 bool RobotModelPlugin::initialize(const vigir_generic_params::ParameterSet& params)
15 {
16  if (!Plugin::initialize(params))
17  return false;
18 
19  // get foot dimensions
21 
22  // get upper body dimensions
25 
26  return true;
27 }
28 
30 {
31  return true;
32 }
33 
34 const geometry_msgs::Vector3& RobotModelPlugin::getFootSize() const
35 {
36  return foot_size_;
37 }
38 
39 const geometry_msgs::Vector3& RobotModelPlugin::getUpperBodySize() const
40 {
41  return upper_body_size_;
42 }
43 
44 const geometry_msgs::Vector3& RobotModelPlugin::getUpperBodyOriginShift() const
45 {
47 }
48 }
const geometry_msgs::Vector3 & getUpperBodySize() const
bool getFootSize(ros::NodeHandle &nh, geometry_msgs::Vector3 &foot_size)
bool getUpperBodyOriginShift(ros::NodeHandle &nh, geometry_msgs::Vector3 &upper_body_origin_shift)
bool initialize(const vigir_generic_params::ParameterSet &params=vigir_generic_params::ParameterSet()) override
bool getUpperBodySize(ros::NodeHandle &nh, geometry_msgs::Vector3 &upper_body_size)
const geometry_msgs::Vector3 & getFootSize() const
const geometry_msgs::Vector3 & getUpperBodyOriginShift() const


vigir_footstep_planning_plugins
Author(s): Alexander Stumpf
autogenerated on Mon Jun 10 2019 15:47:39