34 #include <Eigen/Geometry> 35 #include <Eigen/Dense> 38 #include <visualization_msgs/MarkerArray.h> 60 tempMarker.action = visualization_msgs::Marker::ADD;
68 virtual void drawPoint(
const Eigen::Vector2f& pointWorldFrame)
72 tempMarker.pose.position.x = pointWorldFrame.x();
73 tempMarker.pose.position.y = pointWorldFrame.y();
77 tempMarker.type = visualization_msgs::Marker::CUBE;
84 virtual void drawArrow(
const Eigen::Vector3f& poseWorld)
91 tempMarker.pose.orientation.w = cos(poseWorld.z()*0.5f);
92 tempMarker.pose.orientation.z = sin(poseWorld.z()*0.5f);
94 tempMarker.type = visualization_msgs::Marker::ARROW;
102 virtual void drawCovariance(
const Eigen::Vector2f& mean,
const Eigen::Matrix2f& covMatrix)
108 Eigen::SelfAdjointEigenSolver<Eigen::Matrix2f> eig(covMatrix);
110 const Eigen::Vector2f& eigValues (eig.eigenvalues());
111 const Eigen::Matrix2f& eigVectors (eig.eigenvectors());
113 float angle = (atan2(eigVectors(1, 0), eigVectors(0, 0)));
115 tempMarker.type = visualization_msgs::Marker::CYLINDER;
117 double lengthMajor = sqrt(eigValues[0]);
118 double lengthMinor = sqrt(eigValues[1]);
125 tempMarker.pose.orientation.w = cos(angle*0.5);
126 tempMarker.pose.orientation.z = sin(angle*0.5);
132 virtual void drawCovariance(
const Eigen::Vector3f& mean,
const Eigen::Matrix3f& covMatrix)
134 tempMarker.type = visualization_msgs::Marker::SPHERE;
143 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eig(covMatrix);
145 const Eigen::Vector3f& eigValues (eig.eigenvalues());
146 const Eigen::Matrix3f& eigVectors (eig.eigenvectors());
149 Eigen::Matrix3f eigVectorsFlipped;
150 eigVectorsFlipped.col(0) = eigVectors.col(2);
151 eigVectorsFlipped.col(1) = eigVectors.col(1);
152 eigVectorsFlipped.col(2) = eigVectors.col(0);
154 if (eigVectorsFlipped.determinant() < 0){
155 eigVectorsFlipped.col(2) = -eigVectorsFlipped.col(2);
158 Eigen::Quaternionf quaternion (eigVectorsFlipped);
166 tempMarker.pose.orientation.w = quaternion.w();
167 tempMarker.pose.orientation.x = quaternion.x();
168 tempMarker.pose.orientation.y = quaternion.y();
169 tempMarker.pose.orientation.z = quaternion.z();
188 virtual void setColor(
double r,
double g,
double b,
double a = 1.0)
196 virtual void addMarker(visualization_msgs::Marker marker) {
197 if (marker.id == 0) marker.id =
idCounter++;
198 if (marker.ns.empty()) marker.ns =
tempMarker.ns;
202 virtual void addMarkers(visualization_msgs::MarkerArray markers) {
203 for(visualization_msgs::MarkerArray::_markers_type::iterator it = markers.markers.begin(); it != markers.markers.end(); ++it) {
204 visualization_msgs::Marker &marker = *it;
225 for(visualization_msgs::MarkerArray::_markers_type::iterator it =
allMarkers.markers.begin(); it !=
allMarkers.markers.end(); ++it)
227 it->action = visualization_msgs::Marker::DELETE;
visualization_msgs::MarkerArray markerArray
void publish(const boost::shared_ptr< M > &message) const
virtual void sendAndResetData()
virtual void setScale(double scale)
virtual void drawPoint(const Eigen::Vector2f &pointWorldFrame)
visualization_msgs::Marker tempMarker
virtual void drawCovariance(const Eigen::Vector3f &mean, const Eigen::Matrix3f &covMatrix)
virtual void setNamespace(const std::string &ns)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual void addMarker(visualization_msgs::Marker marker)
virtual void drawCovariance(const Eigen::Vector2f &mean, const Eigen::Matrix2f &covMatrix)
virtual void addMarkers(visualization_msgs::MarkerArray markers)
visualization_msgs::MarkerArray allMarkers
virtual void setColor(double r, double g, double b, double a=1.0)
void setTime(const ros::Time &time)
ros::Publisher markerArrayPublisher_
virtual void drawArrow(const Eigen::Vector3f &poseWorld)
ros::Publisher markerPublisher_