viz.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 // Author: Michael Ferguson
18 
19 #include <ros/ros.h>
21 #include <sensor_msgs/JointState.h>
22 #include <sensor_msgs/PointCloud2.h>
23 #include <visualization_msgs/MarkerArray.h>
24 
25 #include <urdf/model.h>
27 
32 
33 int main(int argc, char** argv)
34 {
35  // What bag to visualize
36  if (argc == 1)
37  {
38  std::cerr << std::endl;
39  std::cerr << "usage:" << std::endl;
40  std::cerr << " viz calibration_data.bag [offsets.yaml]" << std::endl;
41  std::cerr << std::endl;
42  return -1;
43  }
44  std::string bag_name = argv[1];
45 
46  // Start up ROS
47  ros::init(argc, argv, "robot_calibration_viz");
48  ros::NodeHandle nh("~");
49 
50  // Publisher of fake joint states (latched)
51  ros::Publisher state = nh.advertise<sensor_msgs::JointState>("/fake_controller_joint_states", 1, true);
52 
53  // Publisher of visualization (latched)
54  ros::Publisher pub = nh.advertise<visualization_msgs::MarkerArray>("data", 10, true);
55 
56  // The calibration data
57  std_msgs::String description_msg;
58  std::vector<robot_calibration_msgs::CalibrationData> data;
59  if (!robot_calibration::load_bag(bag_name, description_msg, data))
60  {
61  // Error will be printed in function
62  return -1;
63  }
64 
65  // Load KDL from URDF
66  urdf::Model model;
67  KDL::Tree tree;
68  if (!model.initString(description_msg.data))
69  {
70  ROS_FATAL("Failed to parse URDF.");
71  return -1;
72  }
73  if (!kdl_parser::treeFromUrdfModel(model, tree))
74  {
75  ROS_FATAL("Failed to construct KDL tree");
76  return -1;
77  }
78 
79  // Get parameters
82  params.LoadFromROS(nh);
83  ROS_INFO_STREAM("Publishing markers in " << params.base_link << " frame.");
84 
85  // Create models for reprojection
86  std::map<std::string, robot_calibration::ChainModel*> models;
87  std::map<std::string, ros::Publisher> camera_pubs;
88  std::vector<std::string> model_names;
89  for (size_t i = 0; i < params.models.size(); ++i)
90  {
91  if (params.models[i].type == "chain")
92  {
93  ROS_INFO_STREAM("Creating chain '" << params.models[i].name << "' from " <<
94  params.base_link << " to " <<
95  params.models[i].params["frame"]);
96  robot_calibration::ChainModel* model = new robot_calibration::ChainModel(params.models[i].name, tree, params.base_link, params.models[i].params["frame"]);
97  models[params.models[i].name] = model;
98  model_names.push_back(params.models[i].name);
99  }
100  else if (params.models[i].type == "camera3d")
101  {
102  ROS_INFO_STREAM("Creating camera3d '" << params.models[i].name << "' in frame " <<
103  params.models[i].params["frame"]);
104  std::string param_name = params.models[i].params["param_name"];
105  if (param_name == "")
106  {
107  // Default to same name as sensor
108  param_name = params.models[i].name;
109  }
110  robot_calibration::Camera3dModel* model = new robot_calibration::Camera3dModel(params.models[i].name, param_name, tree, params.base_link, params.models[i].params["frame"]);
111  models[params.models[i].name] = model;
112  model_names.push_back(params.models[i].name);
113  camera_pubs[params.models[i].name] = nh.advertise<sensor_msgs::PointCloud2>(params.models[i].name, 1);
114  }
115  else
116  {
117  // ERROR unknown
118  }
119  }
120 
121  // Setup our colors
122  std::vector<std_msgs::ColorRGBA> model_colors;
123  {
124  // Index 0 is white -- used for first points
125  std_msgs::ColorRGBA color;
126  color.r = 1.0;
127  color.b = 1.0;
128  color.g = 1.0;
129  color.a = 1.0;
130  model_colors.push_back(color);
131  while (model_colors.size() < model_names.size() + 1)
132  {
133  // Red
134  std_msgs::ColorRGBA color;
135  color.r = 1;
136  color.g = 0;
137  color.b = 0;
138  color.a = 1;
139  model_colors.push_back(color);
140  // Green
141  color.r = 0;
142  color.g = 1;
143  color.b = 0;
144  color.a = 1;
145  model_colors.push_back(color);
146  // Green
147  color.r = 0;
148  color.g = 0;
149  color.b = 1;
150  color.a = 1;
151  model_colors.push_back(color);
152  }
153  }
154 
155  // Load initial values for offsets (if any)
156  for (size_t i = 0; i < params.free_params.size(); ++i)
157  {
158  offsets.add(params.free_params[i]);
159  }
160  for (size_t i = 0; i < params.free_frames.size(); ++i)
161  {
162  offsets.addFrame(params.free_frames[i].name,
163  params.free_frames[i].x,
164  params.free_frames[i].y,
165  params.free_frames[i].z,
166  params.free_frames[i].roll,
167  params.free_frames[i].pitch,
168  params.free_frames[i].yaw);
169  }
170  for (size_t i = 0; i < params.free_frames_initial_values.size(); ++i)
171  {
172  if (!offsets.setFrame(params.free_frames_initial_values[i].name,
173  params.free_frames_initial_values[i].x,
174  params.free_frames_initial_values[i].y,
175  params.free_frames_initial_values[i].z,
176  params.free_frames_initial_values[i].roll,
177  params.free_frames_initial_values[i].pitch,
178  params.free_frames_initial_values[i].yaw))
179  {
180  ROS_ERROR_STREAM("Error setting initial value for " <<
181  params.free_frames_initial_values[i].name);
182  }
183  }
184 
185  // Load final values for offsets (if requested)
186  if (argc == 3)
187  {
188  std::string offsets_yaml = argv[2];
189  if (!offsets.loadOffsetYAML(offsets_yaml))
190  {
191  ROS_FATAL("Unable to load offsets from YAML");
192  return -1;
193  }
194  }
195 
196  // Publish messages
197  for (size_t i = 0; i < data.size(); ++i)
198  {
199  // Break out if ROS is dead
200  if (!ros::ok())
201  break;
202 
203  // Publish a marker array
204  visualization_msgs::MarkerArray markers;
205  for (size_t m = 0; m < model_names.size(); ++m)
206  {
207  // Project through model
208  std::vector<geometry_msgs::PointStamped> points;
209  points = models[model_names[m]]->project(data[i], offsets);
210 
211  if (points.empty())
212  {
213  continue;
214  }
215 
216  // Convert into marker
217  visualization_msgs::Marker msg;
218  msg.header.frame_id = params.base_link;
219  msg.header.stamp = ros::Time::now();
220  msg.ns = model_names[m];
221  msg.id = m;
222  msg.type = msg.SPHERE_LIST;
223  msg.pose.orientation.w = 1.0;
224  msg.scale.x = 0.01;
225  msg.scale.y = 0.01;
226  msg.scale.z = 0.01;
227  msg.points.push_back(points[0].point);
228  msg.colors.push_back(model_colors[0]);
229  for (size_t p = 1; p < points.size(); ++p)
230  {
231  msg.points.push_back(points[p].point);
232  msg.colors.push_back(model_colors[m+1]);
233  }
234  markers.markers.push_back(msg);
235  }
236  pub.publish(markers);
237 
238  // Publish the joint states
239  sensor_msgs::JointState state_msg = data[i].joint_states;
240  for (size_t j = 0; j < state_msg.name.size(); ++j)
241  {
242  double offset = offsets.get(state_msg.name[j]);
243  state_msg.position[j] += offset;
244  }
245  state.publish(state_msg);
246 
247  // Publish sensor data (if present)
248  for (size_t obs = 0; obs < data[i].observations.size(); ++obs)
249  {
250  if (data[i].observations[obs].cloud.height != 0)
251  {
252  auto pub = camera_pubs.find(data[i].observations[obs].sensor_name);
253  if (pub != camera_pubs.end())
254  {
255  pub->second.publish(data[i].observations[obs].cloud);
256  }
257  }
258  }
259 
260  // Wait to proceed
261  std::cout << "Press enter to continue...";
262  std::string throwaway;
263  std::getline(std::cin, throwaway);
264  }
265 
266  return 0;
267 }
ros::Publisher
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
load_bag.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
robot_calibration::CalibrationOffsetParser
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
Definition: offset_parser.h:33
ros.h
robot_calibration::OptimizationParams::free_frames_initial_values
std::vector< FreeFrameInitialValue > free_frames_initial_values
Definition: optimization_params.h:63
robot_calibration::CalibrationOffsetParser::add
bool add(const std::string name)
Tell the parser we wish to calibrate an active joint or other single parameter.
Definition: calibration_offset_parser.cpp:37
offset_parser.h
urdf::Model
robot_calibration::CalibrationOffsetParser::setFrame
bool setFrame(const std::string name, double x, double y, double z, double roll, double pitch, double yaw)
Set the values for a frame.
Definition: calibration_offset_parser.cpp:104
robot_calibration::OptimizationParams::free_params
std::vector< std::string > free_params
Definition: optimization_params.h:61
kdl_parser::treeFromUrdfModel
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
robot_calibration::CalibrationOffsetParser::addFrame
bool addFrame(const std::string name, bool calibrate_x, bool calibrate_y, bool calibrate_z, bool calibrate_roll, bool calibrate_pitch, bool calibrate_yaw)
Tell the parser we wish to calibrate a fixed joint.
Definition: calibration_offset_parser.cpp:66
robot_calibration::CalibrationOffsetParser::loadOffsetYAML
bool loadOffsetYAML(const std::string &filename)
Load all the current offsets from a YAML.
Definition: calibration_offset_parser.cpp:189
robot_calibration::OptimizationParams::LoadFromROS
bool LoadFromROS(ros::NodeHandle &nh)
Definition: optimization_params.cpp:30
model.h
robot_calibration::OptimizationParams::base_link
std::string base_link
Definition: optimization_params.h:60
chain.h
urdf::Model::initString
URDF_EXPORT bool initString(const std::string &xmlstring)
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ROS_FATAL
#define ROS_FATAL(...)
robot_calibration::OptimizationParams::free_frames
std::vector< FreeFrameParams > free_frames
Definition: optimization_params.h:62
kdl_parser.hpp
point
std::chrono::system_clock::time_point point
robot_calibration::OptimizationParams
Class to hold parameters for optimization.
Definition: optimization_params.h:29
robot_calibration::load_bag
bool load_bag(const std::string &file_name, std_msgs::String &description_msg, std::vector< robot_calibration_msgs::CalibrationData > &data)
Load a bagfile of calibration data.
Definition: load_bag.h:42
robot_calibration::CalibrationOffsetParser::get
double get(const std::string name) const
Get the offset.
Definition: calibration_offset_parser.cpp:139
optimization_params.h
robot_calibration::OptimizationParams::models
std::vector< Params > models
Definition: optimization_params.h:64
robot_calibration::Camera3dModel
Model of a camera on a kinematic chain.
Definition: camera3d.h:31
camera3d.h
ros::NodeHandle
ros::Time::now
static Time now()
robot_calibration::ChainModel
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
Definition: chain.h:107
main
int main(int argc, char **argv)
Definition: viz.cpp:33


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01