21 #include <sensor_msgs/JointState.h> 22 #include <sensor_msgs/PointCloud2.h> 23 #include <visualization_msgs/MarkerArray.h> 33 int main(
int argc,
char** argv)
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;
44 std::string bag_name = argv[1];
47 ros::init(argc, argv,
"robot_calibration_viz");
57 std_msgs::String description_msg;
58 std::vector<robot_calibration_msgs::CalibrationData> data;
75 ROS_FATAL(
"Failed to construct KDL tree");
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)
91 if (params.
models[i].type ==
"chain")
95 params.
models[i].params[
"frame"]);
97 models[params.
models[i].name] = model;
98 model_names.push_back(params.
models[i].name);
100 else if (params.
models[i].type ==
"camera3d")
103 params.
models[i].params[
"frame"]);
104 std::string param_name = params.
models[i].params[
"param_name"];
105 if (param_name ==
"")
108 param_name = params.
models[i].name;
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);
122 std::vector<std_msgs::ColorRGBA> model_colors;
125 std_msgs::ColorRGBA color;
130 model_colors.push_back(color);
131 while (model_colors.size() < model_names.size() + 1)
134 std_msgs::ColorRGBA color;
139 model_colors.push_back(color);
145 model_colors.push_back(color);
151 model_colors.push_back(color);
156 for (
size_t i = 0; i < params.
free_params.size(); ++i)
160 for (
size_t i = 0; i < params.
free_frames.size(); ++i)
188 std::string offsets_yaml = argv[2];
191 ROS_FATAL(
"Unable to load offsets from YAML");
197 for (
size_t i = 0; i < data.size(); ++i)
204 visualization_msgs::MarkerArray markers;
205 for (
size_t m = 0; m < model_names.size(); ++m)
208 std::vector<geometry_msgs::PointStamped> points;
209 points = models[model_names[m]]->project(data[i], offsets);
217 visualization_msgs::Marker msg;
220 msg.ns = model_names[m];
222 msg.type = msg.SPHERE_LIST;
223 msg.pose.orientation.w = 1.0;
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)
231 msg.points.push_back(points[p].point);
232 msg.colors.push_back(model_colors[m+1]);
234 markers.markers.push_back(msg);
236 pub.publish(markers);
239 sensor_msgs::JointState state_msg = data[i].joint_states;
240 for (
size_t j = 0; j < state_msg.name.size(); ++j)
242 double offset = offsets.
get(state_msg.name[j]);
243 state_msg.position[j] += offset;
248 for (
size_t obs = 0; obs < data[i].observations.size(); ++obs)
250 if (data[i].observations[obs].cloud.height != 0)
252 auto pub = camera_pubs.find(data[i].observations[obs].sensor_name);
253 if (pub != camera_pubs.end())
255 pub->second.publish(data[i].observations[obs].cloud);
261 std::cout <<
"Press enter to continue...";
262 std::string throwaway;
263 std::getline(std::cin, throwaway);
URDF_EXPORT bool initString(const std::string &xmlstring)
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
Class to hold parameters for optimization.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< FreeFrameInitialValue > free_frames_initial_values
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
double get(const std::string name) const
Get the offset.
std::vector< std::string > free_params
bool LoadFromROS(ros::NodeHandle &nh)
void publish(const boost::shared_ptr< M > &message) const
bool add(const std::string name)
Tell the parser we wish to calibrate an active joint or other single parameter.
bool setFrame(const std::string name, double x, double y, double z, double roll, double pitch, double yaw)
Set the values for a frame.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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.
std::vector< FreeFrameParams > free_frames
Model of a camera on a kinematic chain.
std::vector< Params > models
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.
int main(int argc, char **argv)
#define ROS_INFO_STREAM(args)
#define ROS_ERROR_STREAM(args)
bool loadOffsetYAML(const std::string &filename)
Load all the current offsets from a YAML.
Model of a kinematic chain. This is the basic instance where we transform the world observations into...