visualization.cpp
Go to the documentation of this file.
1 
6 /*
7  * Copyright 2014,2015 M.H.Kabir
8  *
9  * This file is part of the mavros package and subject to the license terms
10  * in the top-level LICENSE file of the mavros repository.
11  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
12  */
13 
14 #include <vector>
15 
16 #include <tf/tf.h>
17 
18 #include <ros/ros.h>
19 #include <ros/console.h>
20 
21 #include <geometry_msgs/PoseStamped.h>
22 #include <geometry_msgs/Vector3Stamped.h>
23 #include <visualization_msgs/Marker.h>
24 #include <visualization_msgs/MarkerArray.h>
25 
26 // parameters
27 static std::string fixed_frame_id;
28 static std::string child_frame_id;
29 static double marker_scale;
30 static int max_track_size = 100;
31 
32 // source subscribers
36 
37 // marker publishers
42 
43 // landing target marker size
44 geometry_msgs::Vector3 lt_size;
45 
47 
52 {
54 
55  if ( !track_marker )
56  {
57  track_marker = boost::make_shared<visualization_msgs::Marker>();
58  track_marker->type = visualization_msgs::Marker::CUBE_LIST;
59  track_marker->ns = "fcu";
60  track_marker->action = visualization_msgs::Marker::ADD;
61  track_marker->scale.x = marker_scale * 0.015;
62  track_marker->scale.y = marker_scale * 0.015;
63  track_marker->scale.z = marker_scale * 0.015;
64  track_marker->color.a = 1.0;
65  track_marker->color.r = 0.0;
66  track_marker->color.g = 0.0;
67  track_marker->color.b = 0.5;
68  track_marker->points.reserve(max_track_size);
69  }
70 
71  static int marker_idx = 0;
72 
73  if ( track_marker->points.size() < max_track_size )
74  track_marker->points.push_back(pose->pose.position);
75  else track_marker->points[marker_idx] = pose->pose.position;
76 
77  marker_idx = ++marker_idx % max_track_size;
78 
79  track_marker->header = pose->header;
80  track_marker_pub.publish(track_marker);
81 }
82 
84 {
86 
87  if ( !marker ) // only instantiate marker once
88  {
89  marker = boost::make_shared<visualization_msgs::Marker>();
90 
91  marker->header = wp->header;
92  marker->header.frame_id = fixed_frame_id;
93  marker->type = visualization_msgs::Marker::ARROW;
94  marker->ns = "wp";
95  marker->action = visualization_msgs::Marker::ADD;
96  marker->scale.x = marker_scale * 1.0;
97  marker->scale.y = marker_scale * 0.1;
98  marker->scale.z = marker_scale * 0.1;
99 
100  marker->color.a = 1.0;
101  marker->color.r = 0.0;
102  marker->color.g = 1.0;
103  marker->color.b = 0.0;
104  }
105 
106  marker->pose = wp->pose;
107  wp_marker_pub.publish(marker);
108 }
109 
110 
115 {
116  static int marker_id = 2; // TODO: generate new marker for each target
117 
118  auto marker = boost::make_shared<visualization_msgs::Marker>();
119 
120  marker->header = target->header;
121  marker->ns = "landing_target";
122  marker->id = marker_id;
123  marker->type = visualization_msgs::Marker::CUBE;
124  marker->action = visualization_msgs::Marker::ADD;
125 
126  marker->color.a = 1.0;
127  marker->color.r = 1.0;
128  marker->color.g = 0.0;
129  marker->color.b = 0.0;
130 
131  marker->scale.x = 1.0;
132  marker->scale.y = 1.0;
133  marker->scale.z = 1.0;
134 
135  // origin
136  marker->pose = target->pose;
137  lt_marker_pub.publish(marker);
138 
139  // cross arms
140  marker->pose.position.x = lt_size.x;
141  marker->pose.position.y = lt_size.y;
142  marker->pose.position.z = lt_size.z;
143 
144  marker->id = ++marker_id;
145  marker->pose.orientation.w = 0;
146  marker->pose.orientation.x = 0;
147  marker->pose.orientation.y = 0;
148  marker->pose.orientation.w = 0;
149  lt_marker_pub.publish(marker);
150 
151  marker->id = ++marker_id;
152  // 90 degrees rotation
153  marker->pose.orientation.w = 0.70711;
154  marker->pose.orientation.x = 0;
155  marker->pose.orientation.y = 0;
156  marker->pose.orientation.w = 0.70711;
157  lt_marker_pub.publish(marker);
158 }
159 
163 static void create_vehicle_markers( int num_rotors, float arm_len, float body_width, float body_height )
164 {
165  if ( num_rotors <= 0 ) num_rotors = 2;
166 
171  if ( vehicle_marker )
172  return;
173 
174  vehicle_marker = boost::make_shared<visualization_msgs::MarkerArray>();
175  vehicle_marker->markers.reserve( 2 * num_rotors + 1 );
176 
181  // rotor marker template
182  visualization_msgs::Marker rotor;
183  rotor.header.stamp = ros::Time();
184  rotor.header.frame_id = child_frame_id;
185  rotor.ns = "vehicle_rotor";
186  rotor.action = visualization_msgs::Marker::ADD;
187  rotor.type = visualization_msgs::Marker::CYLINDER;
188  rotor.scale.x = 0.2 * marker_scale;
189  rotor.scale.y = 0.2 * marker_scale;
190  rotor.scale.z = 0.01 * marker_scale;
191  rotor.color.r = 0.4;
192  rotor.color.g = 0.4;
193  rotor.color.b = 0.4;
194  rotor.color.a = 0.8;
195  rotor.pose.position.z = 0;
196 
197  // arm marker template
198  visualization_msgs::Marker arm;
199  arm.header.stamp = ros::Time();
200  arm.header.frame_id = child_frame_id;
201  arm.ns = "vehicle_arm";
202  arm.action = visualization_msgs::Marker::ADD;
203  arm.type = visualization_msgs::Marker::CUBE;
204  arm.scale.x = arm_len * marker_scale;
205  arm.scale.y = 0.02 * marker_scale;
206  arm.scale.z = 0.01 * marker_scale;
207  arm.color.r = 0.0;
208  arm.color.g = 0.0;
209  arm.color.b = 1.0;
210  arm.color.a = 1.0;
211  arm.pose.position.z = -0.015 * marker_scale;
212 
213  float angle_increment = 2 * M_PI / num_rotors;
214 
215  for ( float angle = angle_increment / 2; angle <= (2 * M_PI); angle += angle_increment )
216  {
217  rotor.pose.position.x = arm_len * cos(angle) * marker_scale;
218  rotor.pose.position.y = arm_len * sin(angle) * marker_scale;
219  rotor.id++;
220 
221  arm.pose.position.x = rotor.pose.position.x / 2;
222  arm.pose.position.y = rotor.pose.position.y / 2;
223  arm.pose.orientation = tf::createQuaternionMsgFromYaw(angle);
224  arm.id++;
225 
226  vehicle_marker->markers.push_back(rotor);
227  vehicle_marker->markers.push_back(arm);
228  }
229 
230  // body marker template
231  visualization_msgs::Marker body;
232  body.header.stamp = ros::Time();
233  body.header.frame_id = child_frame_id;
234  body.ns = "vehicle_body";
235  body.action = visualization_msgs::Marker::ADD;
236  body.type = visualization_msgs::Marker::CUBE;
237  body.scale.x = body_width * marker_scale;
238  body.scale.y = body_width * marker_scale;
239  body.scale.z = body_height * marker_scale;
240  body.color.r = 0.0;
241  body.color.g = 1.0;
242  body.color.b = 0.0;
243  body.color.a = 0.8;
244 
245  vehicle_marker->markers.push_back(body);
246 }
247 
249 {
250  publish_track_marker(pose);
251  if (vehicle_marker) vehicle_marker_pub.publish(vehicle_marker);
252 }
253 
255 {
256  publish_wp_marker(wp);
257 }
258 
260 {
261  publish_lt_marker(target);
262 }
263 
265 {
266  lt_size = lt_marker->vector;
267 }
268 
269 int main(int argc, char *argv[])
270 {
271  ros::init(argc, argv, "copter_visualization");
273  ros::NodeHandle priv_nh("~");
274 
275  int num_rotors;
276  double arm_len, body_width, body_height;
277 
278  priv_nh.param<std::string>("fixed_frame_id", fixed_frame_id, "map");
279  priv_nh.param<std::string>("child_frame_id", child_frame_id, "base_link");
280 
281  priv_nh.param("marker_scale", marker_scale, 1.0);
282  priv_nh.param("num_rotors", num_rotors, 6);
283  priv_nh.param("arm_len", arm_len, 0.22 );
284  priv_nh.param("body_width", body_width, 0.15 );
285  priv_nh.param("body_height", body_height, 0.10 );
286  priv_nh.param("max_track_size", max_track_size, 1000 );
287 
288  create_vehicle_markers( num_rotors, arm_len, body_width, body_height );
289 
290  track_marker_pub = nh.advertise<visualization_msgs::Marker>("track_markers", 10);
291  vehicle_marker_pub = nh.advertise<visualization_msgs::MarkerArray>("vehicle_marker", 10);
292  wp_marker_pub = nh.advertise<visualization_msgs::Marker>("wp_markers", 10);
293  lt_marker_pub = nh.advertise<visualization_msgs::Marker>("landing_target", 10);
294 
295  auto pos_sub = nh.subscribe("local_position", 10, local_position_sub_cb);
296  auto wp_sub = nh.subscribe("local_setpoint", 10, setpoint_local_pos_sub_cb);
297  lt_marker_sub = nh.subscribe("lt_marker", 10, lt_marker_sub_cb);
298 
299  ros::spin();
300  return 0;
301 }
static void landing_target_sub_cb(const geometry_msgs::PoseStamped::ConstPtr &target)
std::shared_ptr< MAVConnInterface const > ConstPtr
ros::NodeHandle nh
void publish(const boost::shared_ptr< M > &message) const
static std::string child_frame_id
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber lt_marker_sub
void setpoint_local_pos_sub_cb(const geometry_msgs::PoseStamped::ConstPtr &wp)
static void publish_lt_marker(const geometry_msgs::PoseStamped::ConstPtr &target)
publish landing target marker
static void local_position_sub_cb(const geometry_msgs::PoseStamped::ConstPtr &pose)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
geometry_msgs::Vector3 lt_size
ros::Subscriber landing_target_sub
boost::shared_ptr< visualization_msgs::MarkerArray > vehicle_marker
static int max_track_size
static void publish_wp_marker(const geometry_msgs::PoseStamped::ConstPtr &wp)
static void create_vehicle_markers(int num_rotors, float arm_len, float body_width, float body_height)
publish vehicle
static std::string fixed_frame_id
static void lt_marker_sub_cb(const geometry_msgs::Vector3Stamped::ConstPtr &lt_marker)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char *argv[])
static double marker_scale
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher lt_marker_pub
ros::Subscriber local_position_sub
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
ros::Publisher wp_marker_pub
static void publish_track_marker(const geometry_msgs::PoseStamped::ConstPtr &pose)
publish vehicle track
ros::Publisher track_marker_pub
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
ros::Publisher vehicle_marker_pub
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:18