sr_movements.cpp
Go to the documentation of this file.
1 
29 #include <ros/ros.h>
30 
33 
34 #include <string>
35 #include <iostream>
36 
37 
38 int main(int argc, char *argv[])
39 {
40  ros::init(argc, argv, "sr_movements");
41 
42  ros::NodeHandle nh_tilde("~");
43  std::string img_path;
44 
45  if (nh_tilde.getParam("image_path", img_path))
46  {
47  shadowrobot::MovementFromImage mvt_im(img_path);
48 
49  double min, max, publish_rate;
50  if (!nh_tilde.getParam("publish_rate", publish_rate))
51  publish_rate = 100.0;
52 
53  int repetition;
54  if (!nh_tilde.getParam("repetition", repetition))
55  repetition = 1;
56 
57  int nb_mvt_step;
58  if (!nh_tilde.getParam("nb_step", nb_mvt_step))
59  nb_mvt_step = 1000;
60 
61  std::string controller_type;
62  if (!nh_tilde.getParam("msg_type", controller_type))
63  controller_type = "";
64 
65  std::string joint_name;
66  if (!nh_tilde.getParam("joint_name", joint_name))
67  {
68  // for compatibility, if no joint_name is provided, then we use the
69  // provided min and max to instantiate the movement publisher
70  // which will use the remapped topics.
71  if (!nh_tilde.getParam("min", min))
72  min = 0.0;
73  if (!nh_tilde.getParam("max", max))
74  max = 1.5;
75 
76  shadowrobot::MovementPublisher mvt_pub(min, max, publish_rate,
77  static_cast<unsigned int>(repetition),
78  static_cast<unsigned int>(nb_mvt_step),
79  controller_type);
80 
81  mvt_pub.add_movement(mvt_im);
82  mvt_pub.start();
83  }
84  else
85  {
86  // check if this is a test using gazebo
87  bool testing;
88  if (!nh_tilde.getParam("testing", testing))
89  testing = false;
90 
91  // This is the new easier to implement version of the movement
92  // publisher. Simply uses the name of the joint to instantiate
93  // the MovementPublisher, grabbing min, max and topics from the
94  // HandCommander.
95  shadowrobot::MovementPublisher mvt_pub(joint_name, publish_rate,
96  static_cast<unsigned int>(repetition),
97  static_cast<unsigned int>(nb_mvt_step),
98  controller_type, testing);
99 
100  mvt_pub.add_movement(mvt_im);
101  mvt_pub.start();
102  }
103  }
104  else
105  {
106  ROS_ERROR("No bitmap specified");
107  }
108  return 0;
109 }
110 
111 
112 
113 /* For the emacs weenies in the crowd.
114 Local Variables:
115  c-basic-offset: 2
116 End:
117 */
void add_movement(PartialMovement mvt)
Publishes a sequence of movements.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char *argv[])
Reads a png file and creates a movement from it.
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR(...)


sr_movements
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:50:46