29 #ifndef HECTOR_DRAWINGS_H__ 30 #define HECTOR_DRAWINGS_H__ 37 #include <visualization_msgs/MarkerArray.h> 39 #include <Eigen/Dense> 61 tempMarker.action = visualization_msgs::Marker::ADD;
64 virtual void drawPoint(
const Eigen::Vector2f& pointWorldFrame)
68 tempMarker.pose.position.x = pointWorldFrame.x();
69 tempMarker.pose.position.y = pointWorldFrame.y();
73 tempMarker.type = visualization_msgs::Marker::CUBE;
80 virtual void drawArrow(
const Eigen::Vector3f& poseWorld)
90 tempMarker.type = visualization_msgs::Marker::ARROW;
98 virtual void drawCovariance(
const Eigen::Vector2f& mean,
const Eigen::Matrix2f& covMatrix)
103 Eigen::SelfAdjointEigenSolver<Eigen::Matrix2f> eig(covMatrix);
105 const Eigen::Vector2f& eigValues (eig.eigenvalues());
106 const Eigen::Matrix2f& eigVectors (eig.eigenvectors());
108 float angle = (
atan2(eigVectors(1, 0), eigVectors(0, 0)));
110 tempMarker.type = visualization_msgs::Marker::CYLINDER;
112 double lengthMajor =
sqrt(eigValues[0]);
113 double lengthMinor =
sqrt(eigValues[1]);
141 virtual void setColor(
double r,
double g,
double b,
double a = 1.0)
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
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
virtual void drawCovariance(const Eigen::Vector2f &mean, const Eigen::Matrix2f &covMatrix)
virtual void setColor(double r, double g, double b, double a=1.0)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void setTime(const ros::Time &time)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
ros::Publisher markerArrayPublisher_
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
virtual void drawArrow(const Eigen::Vector3f &poseWorld)
ros::Publisher markerPublisher_