test_controllers.cpp
Go to the documentation of this file.
1 
27 #include <string>
28 
30 {
31 }
32 
34 {
35 }
36 
38 {
39  hw = boost::shared_ptr<pr2_hardware_interface::HardwareInterface>(new pr2_hardware_interface::HardwareInterface());
40 
41  // add a fake FFJ3 actuator
43  actuator->state_.is_enabled_ = true;
44  hw->addActuator(actuator.get());
45 
46  robot = boost::shared_ptr<pr2_mechanism_model::Robot>(new pr2_mechanism_model::Robot(hw.get()));
47 
48  model = boost::shared_ptr<TiXmlDocument>(new TiXmlDocument());
49 
50  ros::NodeHandle rosnode;
51  std::string urdf_param_name;
52  std::string urdf_string;
53  // search and wait for robot_description on param server
54  while (urdf_string.empty())
55  {
56  ROS_DEBUG("Waiting for urdf: %s on the param server.", "sh_description");
57  if (rosnode.searchParam("sh_description", urdf_param_name))
58  {
59  rosnode.getParam(urdf_param_name, urdf_string);
60  ROS_DEBUG("found upstream\n%s\n------\n%s\n------\n%s", "sh_description", urdf_param_name.c_str(),
61  urdf_string.c_str());
62  }
63  else
64  {
65  rosnode.getParam("sh_description", urdf_string);
66  ROS_DEBUG("found in node namespace\n%s\n------\n%s\n------\n%s", "sh_description", urdf_param_name.c_str(),
67  urdf_string.c_str());
68  }
69  usleep(100000);
70  }
71  ROS_DEBUG("Parsing xml...");
72 
73  // initialize TiXmlDocument doc with a string
74  if (!model->Parse(urdf_string.c_str()) && model->Error())
75  {
76  ROS_ERROR("Failed to parse urdf: %s\n",
77  urdf_string.c_str());
78  }
79  else
80  {
81  robot->initXml(model->RootElement());
82 
83  robot_state = boost::shared_ptr<pr2_mechanism_model::RobotState>(new pr2_mechanism_model::RobotState(robot.get()));
84 
85  joint_state = robot_state->getJointState("FFJ3");
86  joint_state->calibrated_ = true;
87 
89  controller->starting();
90 
91  // initialize the controller:
92  joint_state->position_ = 0.0;
93  controller->update();
94  }
95 }
96 
97 /* For the emacs weenies in the crowd.
98  Local Variables:
99  c-basic-offset: 2
100  End:
101 */
boost::shared_ptr< TiXmlDocument > model
pr2_mechanism_model::JointState * joint_state
boost::shared_ptr< pr2_mechanism_model::Robot > robot
boost::shared_ptr< pr2_mechanism_model::RobotState > robot_state
virtual ~TestControllers()
virtual void init_controller()=0
boost::shared_ptr< sr_actuator::SrMotorActuator > actuator
#define ROS_ERROR(...)
boost::shared_ptr< pr2_hardware_interface::HardwareInterface > hw
#define ROS_DEBUG(...)


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58