21 #include <geometry_msgs/PoseStamped.h> 22 #include <geometry_msgs/Vector3Stamped.h> 23 #include <visualization_msgs/Marker.h> 24 #include <visualization_msgs/MarkerArray.h> 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;
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;
71 static int marker_idx = 0;
74 track_marker->points.push_back(pose->pose.position);
75 else track_marker->points[marker_idx] = pose->pose.position;
79 track_marker->header = pose->header;
80 track_marker_pub.
publish(track_marker);
89 marker = boost::make_shared<visualization_msgs::Marker>();
91 marker->header = wp->header;
93 marker->type = visualization_msgs::Marker::ARROW;
95 marker->action = visualization_msgs::Marker::ADD;
100 marker->color.a = 1.0;
101 marker->color.r = 0.0;
102 marker->color.g = 1.0;
103 marker->color.b = 0.0;
106 marker->pose = wp->pose;
116 static int marker_id = 2;
118 auto marker = boost::make_shared<visualization_msgs::Marker>();
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;
126 marker->color.a = 1.0;
127 marker->color.r = 1.0;
128 marker->color.g = 0.0;
129 marker->color.b = 0.0;
131 marker->scale.x = 1.0;
132 marker->scale.y = 1.0;
133 marker->scale.z = 1.0;
136 marker->pose = target->pose;
140 marker->pose.position.x =
lt_size.x;
141 marker->pose.position.y =
lt_size.y;
142 marker->pose.position.z =
lt_size.z;
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;
151 marker->id = ++marker_id;
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;
163 static void create_vehicle_markers(
int num_rotors,
float arm_len,
float body_width,
float body_height,
int prop_direction)
165 if ( num_rotors <= 0 ) num_rotors = 2;
171 if ( vehicle_marker )
174 vehicle_marker = boost::make_shared<visualization_msgs::MarkerArray>();
175 vehicle_marker->markers.reserve( 2 * num_rotors + 1 );
182 visualization_msgs::Marker rotor;
185 rotor.ns =
"vehicle_rotor";
186 rotor.action = visualization_msgs::Marker::ADD;
187 rotor.type = visualization_msgs::Marker::CYLINDER;
191 rotor.pose.position.z = 0;
194 visualization_msgs::Marker arm;
197 arm.ns =
"vehicle_arm";
198 arm.action = visualization_msgs::Marker::ADD;
199 arm.type = visualization_msgs::Marker::CUBE;
209 float angle_increment = 2 * M_PI / num_rotors;
211 for (
float angle = angle_increment / 2;
angle <= (2 * M_PI);
angle += angle_increment )
213 if ( !prop_direction ) {
219 if (
angle <= (M_PI / 2) - 0.0175 ||
angle >= (M_PI * 3 / 2) + 0.0175 ) {
237 arm.pose.position.x = rotor.pose.position.x / 2;
238 arm.pose.position.y = rotor.pose.position.y / 2;
242 vehicle_marker->markers.push_back(rotor);
243 vehicle_marker->markers.push_back(arm);
247 visualization_msgs::Marker body;
250 body.ns =
"vehicle_body";
251 body.action = visualization_msgs::Marker::ADD;
252 body.type = visualization_msgs::Marker::CUBE;
261 vehicle_marker->markers.push_back(body);
267 if (vehicle_marker) vehicle_marker_pub.
publish(vehicle_marker);
285 int main(
int argc,
char *argv[])
287 ros::init(argc, argv,
"copter_visualization");
291 int num_rotors, prop_direction;
292 double arm_len, body_width, body_height;
298 priv_nh.
param(
"num_rotors", num_rotors, 6);
299 priv_nh.
param(
"arm_len", arm_len, 0.22 );
300 priv_nh.
param(
"body_width", body_width, 0.15 );
301 priv_nh.
param(
"body_height", body_height, 0.10 );
303 priv_nh.
param(
"prop_direction", prop_direction, 0);
307 track_marker_pub = nh.
advertise<visualization_msgs::Marker>(
"track_markers", 10);
308 vehicle_marker_pub = nh.
advertise<visualization_msgs::MarkerArray>(
"vehicle_marker", 10);
309 wp_marker_pub = nh.
advertise<visualization_msgs::Marker>(
"wp_markers", 10);
310 lt_marker_pub = nh.
advertise<visualization_msgs::Marker>(
"landing_target", 10);
static void landing_target_sub_cb(const geometry_msgs::PoseStamped::ConstPtr &target)
std::shared_ptr< MAVConnInterface const > ConstPtr
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 std::string fixed_frame_id
static void lt_marker_sub_cb(const geometry_msgs::Vector3Stamped::ConstPtr <_marker)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ROSCPP_DECL void spin(Spinner &spinner)
static void create_vehicle_markers(int num_rotors, float arm_len, float body_width, float body_height, int prop_direction)
publish vehicle
int main(int argc, char *argv[])
static double marker_scale
bool param(const std::string ¶m_name, T ¶m_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)