urdf_model_marker_main.cpp
Go to the documentation of this file.
1 #include "urdf_parser/urdf_parser.h"
2 #include <iostream>
3 #include <memory>
8 #include <geometry_msgs/PoseArray.h>
9 #include <jsk_topic_tools/log_utils.h>
10 
11 using namespace urdf;
12 using namespace std;
13 using namespace im_utils;
14 
16 private:
20  std::shared_ptr<interactive_markers::InteractiveMarkerServer> server_;
21  string model_name_;
23  double scale_factor_;
24  geometry_msgs::PoseStamped pose_stamped_;
25  geometry_msgs::Pose root_offset_;
27  string mode_;
28  string model_file_;
31  string frame_id_;
34  bool display_;
35  map<string, double> initial_pose_map_;
36 
37  typedef std::shared_ptr<UrdfModelMarker> umm_ptr;
40 
41 public:
42  void displayMarkerArrayCB(const geometry_msgs::PoseArrayConstPtr &msg) {
43  std_msgs::Header header = msg->header;
44  geometry_msgs::PoseStamped ps;
45  ps.header = header;
46 
47  int msg_size = msg->poses.size();
48  int umm_vec_size = umm_vec_.size();
49 
50  if (msg_size <= umm_vec_size) {
51  for (int i = 0; i < msg_size; i++) {
52  //change pose
53  ps.pose = msg->poses[i];
54  umm_vec_[i]->setRootPose(ps);
55  }
56  for (int i = msg_size; i< umm_vec_size; i++) {
57  //move far away
58  ps.pose.position.x = ps.pose.position.y = ps.pose.position.z = 1000000;
59  ps.pose.orientation.w = 1;
60  umm_vec_[i]->setRootPose(ps);
61  }
62  }
63  else {
64  for (int i = 0; i < umm_vec_size; i++) {
65  //change pose
66  ps.pose = msg->poses[i];
67  umm_vec_[i]->setRootPose(ps);
68  }
69  for (int i = umm_vec_size; i < msg_size; i++) {
70  //geometry_msgs::PoseStamped pose = msg->poses[i];
71  ps.pose = msg->poses[i];
72  umm_vec_.push_back(umm_ptr(new UrdfModelMarker(model_name_, model_description_, model_file_, header.frame_id, ps, root_offset_, scale_factor_, mode_ , robot_mode_, registration_,fixed_link_, use_robot_description_, use_visible_color_, initial_pose_map_, i, server_)));
73  }
74  }
75  }
76 
77  void init() {
78  //name
79  model_name_.assign(model_config_["name"]);
80 
81  //description
82  model_description_ = "";
83  if (model_config_.hasMember("description")) {
84  model_description_.assign(model_config_["description"]);
85  }
86  //scale
87  scale_factor_ = 1.02;
88  if (model_config_.hasMember("scale")) {
89  scale_factor_ = getXmlValue(model_config_["scale"]);
90  }
91  //pose
92  if (model_config_.hasMember("pose")) {
93  pose_stamped_.pose = getPose(model_config_["pose"]);
94  }
95  else {
96  pose_stamped_.pose = geometry_msgs::Pose();
97  pose_stamped_.pose.orientation.w = 1.0;
98  }
99  pose_stamped_.header.stamp = ros::Time::now();
100 
101  if (model_config_.hasMember("offset")) {
102  root_offset_ = getPose(model_config_["offset"]);
103  }
104  else {
105  root_offset_ = geometry_msgs::Pose();
106  root_offset_.orientation.w = 1.0;
107  }
108 
109  //color
110  use_visible_color_ = false;
111  if (model_config_.hasMember("use_visible_color")) {
112  use_visible_color_ = model_config_["use_visible_color"];
113  }
114  ROS_INFO_STREAM("use_visible_color: " << use_visible_color_);
115  //frame id
116  frame_id_.assign(model_config_["frame-id"]);
117 
118  //mode
119  mode_ = "model";
120  model_file_ = "";
121  registration_ = false;
122  if (model_config_.hasMember("registration")) {
123  registration_ = model_config_["registration"];
124  mode_ = "registration";
125  }
126 
127  if (model_config_.hasMember("fixed_link")) {
128  XmlRpc::XmlRpcValue fixed_links = model_config_["fixed_link"];
129  if (fixed_links.getType() == XmlRpc::XmlRpcValue::TypeString) {
130  fixed_link_.push_back( fixed_links );
131  }
132  else if (fixed_links.getType() == XmlRpc::XmlRpcValue::TypeArray) {
133  for(int i=0; i< fixed_links.size(); i++) {
134  fixed_link_.push_back(fixed_links[i]);
135  }
136  }
137  }
138 
139  if (model_config_.hasMember("model")) {
140  model_file_.assign(model_config_["model"]);
141  }
142  use_robot_description_ = false;
143  if (model_config_.hasMember("use_robot_description")) {
144  model_file_ = "/robot_description";
145  use_robot_description_ = model_config_["use_robot_description"];
146  }
147  if (model_config_.hasMember("model_param")) {
148  use_robot_description_ = true;
149  model_file_.assign(model_config_["model_param"]);
150  }
151  if (model_config_["robot"]) {
152  mode_ = "robot";
153  }
154  if (model_config_.hasMember("mode")) {
155  mode_.assign(model_config_["mode"]);
156  }
157 
158  robot_mode_ = model_config_["robot"];
159 
160  //initial pose
161  if (model_config_.hasMember("initial_joint_state")) {
162  XmlRpc::XmlRpcValue initial_pose = model_config_["initial_joint_state"];
163  for(int i=0; i< initial_pose.size(); i++) {
164  XmlRpc::XmlRpcValue v = initial_pose[i];
165  string name;
166  double position;
167  if (v.hasMember("name") && v.hasMember("position")) {
168  name.assign(v["name"]);
169  position = getXmlValue(v["position"]);
170  initial_pose_map_[name] = position;
171  }
172  }
173  }
174 
175  //default display
176  if (model_config_.hasMember("display")) {
177  display_ = model_config_["display"];
178  }
179  else {
180  display_ = true;
181  }
182  ROS_INFO("Loading model config");
183  ROS_INFO("model_name: %s", model_name_.c_str());
184  ROS_INFO("model_description: %s", model_description_.c_str());
185  ROS_INFO("scale_factor: %f", scale_factor_);
186  ROS_INFO_STREAM("pose_stamped: " << pose_stamped_);
187  ROS_INFO_STREAM("root_offset: " << root_offset_);
188  ROS_INFO_STREAM("frame_id: " << frame_id_);
189  ROS_INFO_STREAM("mode: " << mode_);
190  ROS_INFO_STREAM("registration: " << registration_);
191 
192 
193  //ROS_INFO_STREAM("fixed_link: " << fixed_link_);
194  ROS_INFO_STREAM("model_file: " << model_file_);
195  ROS_INFO_STREAM("use_robot_description: " << use_robot_description_);
196  }
197 
198  void addUrdfMarker() {
199  new UrdfModelMarker(model_name_, model_description_, model_file_, frame_id_, pose_stamped_ ,root_offset_, scale_factor_, mode_ , robot_mode_, registration_,fixed_link_, use_robot_description_, use_visible_color_,initial_pose_map_, -1, server_);
200  }
201 
202  UrdfModelSettings(XmlRpc::XmlRpcValue model, std::shared_ptr<interactive_markers::InteractiveMarkerServer> server) : pnh_("~") {
203  model_config_ = model;
204  server_ = server;
205  init();
206 
207  if (display_) {
208  addUrdfMarker();
209  }
210  display_marker_sub_ = pnh_.subscribe<geometry_msgs::PoseArray> (model_name_ + "/pose_array", 1, boost::bind( &UrdfModelSettings::displayMarkerArrayCB, this, _1));
211  }
212 };
213 
214 
215 
216 int main(int argc, char** argv)
217 {
218  ros::init(argc, argv, "jsk_model_marker_interface");
220  ros::NodeHandle pnh_("~");
221 
222  string server_name;
223  pnh_.param("server_name", server_name, std::string ("") );
224  if (server_name == "") {
225  server_name = ros::this_node::getName();
226  }
227 
228  std::shared_ptr<interactive_markers::InteractiveMarkerServer> server;
229  server.reset( new interactive_markers::InteractiveMarkerServer(server_name, "", false) );
230 
232  pnh_.param("model_config", v, v);
233  for (int i=0; i< v.size(); i++) {
234  new UrdfModelSettings(v[i], server);
235  }
236  ros::spin();
237  return 0;
238 }
239 
240 
XmlRpc::XmlRpcValue::size
int size() const
UrdfModelSettings::addUrdfMarker
void addUrdfMarker()
Definition: urdf_model_marker_main.cpp:198
UrdfModelSettings::model_description_
string model_description_
Definition: urdf_model_marker_main.cpp:22
UrdfModelSettings::server_
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
Definition: urdf_model_marker_main.cpp:20
UrdfModelSettings::use_robot_description_
bool use_robot_description_
Definition: urdf_model_marker_main.cpp:32
UrdfModelSettings::display_marker_sub_
ros::Subscriber display_marker_sub_
Definition: urdf_model_marker_main.cpp:18
msg
msg
UrdfModelSettings::pose_stamped_
geometry_msgs::PoseStamped pose_stamped_
Definition: urdf_model_marker_main.cpp:24
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
UrdfModelSettings::use_visible_color_
bool use_visible_color_
Definition: urdf_model_marker_main.cpp:26
tools.h
UrdfModelSettings::frame_id_
string frame_id_
Definition: urdf_model_marker_main.cpp:31
UrdfModelSettings::display_
bool display_
Definition: urdf_model_marker_main.cpp:34
getXmlValue
double getXmlValue(XmlRpc::XmlRpcValue val)
Definition: interactive_marker_utils.cpp:639
UrdfModelSettings::registration_
bool registration_
Definition: urdf_model_marker_main.cpp:29
UrdfModelSettings::init
void init()
Definition: urdf_model_marker_main.cpp:77
UrdfModelSettings::scale_factor_
double scale_factor_
Definition: urdf_model_marker_main.cpp:23
vector< string >
UrdfModelSettings::initial_pose_map_
map< string, double > initial_pose_map_
Definition: urdf_model_marker_main.cpp:35
UrdfModelSettings::UrdfModelSettings
UrdfModelSettings(XmlRpc::XmlRpcValue model, std::shared_ptr< interactive_markers::InteractiveMarkerServer > server)
Definition: urdf_model_marker_main.cpp:202
UrdfModelSettings::umm_ptr
std::shared_ptr< UrdfModelMarker > umm_ptr
Definition: urdf_model_marker_main.cpp:37
interactive_marker_utils.h
UrdfModelSettings::pnh_
ros::NodeHandle pnh_
Definition: urdf_model_marker_main.cpp:17
UrdfModelSettings::root_offset_
geometry_msgs::Pose root_offset_
Definition: urdf_model_marker_main.cpp:25
UrdfModelMarker
Definition: urdf_model_marker.h:54
XmlRpc::XmlRpcValue::TypeString
TypeString
argv
ROS_INFO ROS_ERROR int pointer * argv
_1
boost::arg< 1 > _1
UrdfModelSettings::model_name_
string model_name_
Definition: urdf_model_marker_main.cpp:21
UrdfModelSettings::model_config_
XmlRpc::XmlRpcValue model_config_
Definition: urdf_model_marker_main.cpp:19
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
UrdfModelSettings::model_file_
string model_file_
Definition: urdf_model_marker_main.cpp:28
header
header
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
vector::size
pointer size
UrdfModelSettings::fixed_link_
vector< string > fixed_link_
Definition: urdf_model_marker_main.cpp:30
XmlRpc::XmlRpcValue::getType
const Type & getType() const
interactive_markers::InteractiveMarkerServer
XmlRpc::XmlRpcValue::TypeArray
TypeArray
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
XmlRpc::XmlRpcValue::hasMember
bool hasMember(const std::string &name) const
UrdfModelSettings
Definition: urdf_model_marker_main.cpp:15
server
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server
Definition: bounding_box_marker.cpp:43
UrdfModelSettings::displayMarkerArrayCB
void displayMarkerArrayCB(const geometry_msgs::PoseArrayConstPtr &msg)
Definition: urdf_model_marker_main.cpp:42
urdf_model_marker.h
urdf
interactive_marker_helpers.h
std
main
int main(int argc, char **argv)
Definition: urdf_model_marker_main.cpp:216
im_utils
Definition: interactive_marker_utils.h:47
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
ROS_INFO
#define ROS_INFO(...)
UrdfModelSettings::mode_
string mode_
Definition: urdf_model_marker_main.cpp:27
UrdfModelSettings::umm_vec
vector< umm_ptr > umm_vec
Definition: urdf_model_marker_main.cpp:38
UrdfModelSettings::robot_mode_
bool robot_mode_
Definition: urdf_model_marker_main.cpp:33
n
GLfloat n[6][3]
XmlRpc::XmlRpcValue
getPose
geometry_msgs::Pose getPose(XmlRpc::XmlRpcValue val)
Definition: interactive_marker_utils.cpp:614
v
GLfloat v[8][3]
ros::NodeHandle
UrdfModelSettings::umm_vec_
umm_vec umm_vec_
Definition: urdf_model_marker_main.cpp:39
ros::Subscriber
init
void init(void)
ros::Time::now
static Time now()


jsk_interactive_marker
Author(s): furuta
autogenerated on Fri Aug 2 2024 08:50:24