Copter visualization. More...
#include <vector>
#include <tf/tf.h>
#include <ros/ros.h>
#include <ros/console.h>
#include <geometry_msgs/PoseStamped.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
Go to the source code of this file.
Functions | |
static void | create_vehicle_markers (int num_rotors, float arm_len, float body_width, float body_height) |
publish vehicle | |
static void | local_position_sub_cb (const geometry_msgs::PoseStamped::ConstPtr &pose) |
int | main (int argc, char *argv[]) |
static void | publish_track_marker (const geometry_msgs::PoseStamped::ConstPtr &pose) |
publish vehicle track | |
static void | publish_wp_marker (const geometry_msgs::PoseStamped::ConstPtr &wp) |
void | setpoint_local_pos_sub_cb (const geometry_msgs::PoseStamped::ConstPtr &wp) |
Variables | |
static std::string | child_frame_id |
static std::string | fixed_frame_id |
static double | marker_scale |
static int | max_track_size = 100 |
ros::Publisher | track_marker_pub |
boost::shared_ptr < visualization_msgs::MarkerArray > | vehicle_marker |
ros::Publisher | vehicle_marker_pub |
ros::Publisher | wp_marker_pub |
Copter visualization.
Definition in file copter_visualization.cpp.
static void create_vehicle_markers | ( | int | num_rotors, |
float | arm_len, | ||
float | body_width, | ||
float | body_height | ||
) | [static] |
publish vehicle
Create markers only once for efficiency TODO use visualization_msgs::MarkerArray?
Hexacopter marker code adapted from libsfly_viz thanks to Markus Achtelik.
Definition at line 104 of file copter_visualization.cpp.
static void local_position_sub_cb | ( | const geometry_msgs::PoseStamped::ConstPtr & | pose | ) | [static] |
Definition at line 189 of file copter_visualization.cpp.
Definition at line 200 of file copter_visualization.cpp.
static void publish_track_marker | ( | const geometry_msgs::PoseStamped::ConstPtr & | pose | ) | [static] |
publish vehicle track
Definition at line 41 of file copter_visualization.cpp.
static void publish_wp_marker | ( | const geometry_msgs::PoseStamped::ConstPtr & | wp | ) | [static] |
Definition at line 73 of file copter_visualization.cpp.
void setpoint_local_pos_sub_cb | ( | const geometry_msgs::PoseStamped::ConstPtr & | wp | ) |
Definition at line 195 of file copter_visualization.cpp.
std::string child_frame_id [static] |
Definition at line 27 of file copter_visualization.cpp.
std::string fixed_frame_id [static] |
Definition at line 26 of file copter_visualization.cpp.
double marker_scale [static] |
Definition at line 28 of file copter_visualization.cpp.
int max_track_size = 100 [static] |
Definition at line 29 of file copter_visualization.cpp.
Definition at line 32 of file copter_visualization.cpp.
boost::shared_ptr<visualization_msgs::MarkerArray> vehicle_marker |
Definition at line 36 of file copter_visualization.cpp.
Definition at line 33 of file copter_visualization.cpp.
Definition at line 34 of file copter_visualization.cpp.