mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
visual_object.h
1#ifndef BATCH_VISUALIZER__VISUAL_OBJECT_H
2#define BATCH_VISUALIZER__VISUAL_OBJECT_H
3
4#include <rclcpp/rclcpp.hpp>
5#include <Eigen/Core>
6#include <std_msgs/msg/color_rgba.hpp>
7#include <geometry_msgs/msg/point.hpp>
9#include <mrs_msgs/msg/path.hpp>
10#include <mrs_msgs/msg/trajectory_reference.hpp>
11
12#define DEFAULT_ELLIPSE_POINTS 64
13
14namespace mrs_lib
15{
16
17 enum MarkerType
18 {
19 POINT = 0,
20 LINE = 1,
21 TRIANGLE = 2
22 };
23
25 {
26
27
28 public:
29 VisualObject(const Eigen::Vector3d& point, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
30 const unsigned long& id, const rclcpp::Node::SharedPtr& node);
31
32 VisualObject(const mrs_lib::geometry::Ray& ray, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
33 const unsigned long& id, const rclcpp::Node::SharedPtr& node);
34
35 VisualObject(const mrs_lib::geometry::Triangle& triangle, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
36 const bool filled, const unsigned long& id, const rclcpp::Node::SharedPtr& node);
37
38 VisualObject(const mrs_lib::geometry::Rectangle& rectangle, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
39 const bool filled, const unsigned long& id, const rclcpp::Node::SharedPtr& node);
40
41 VisualObject(const mrs_lib::geometry::Cuboid& cuboid, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
42 const bool filled, const unsigned long& id, const rclcpp::Node::SharedPtr& node);
43
44 VisualObject(const mrs_lib::geometry::Ellipse& ellipse, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
45 const bool filled, const unsigned long& id, const rclcpp::Node::SharedPtr& node, const int num_points = DEFAULT_ELLIPSE_POINTS);
46
47 VisualObject(const mrs_lib::geometry::Cylinder& cylinder, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
48 const bool filled, const bool capped, const unsigned long& id, const rclcpp::Node::SharedPtr& node,
49 const int num_sides = DEFAULT_ELLIPSE_POINTS);
50
51 VisualObject(const mrs_lib::geometry::Cone& cone, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
52 const bool filled, const bool capped, const unsigned long& id, const rclcpp::Node::SharedPtr& node,
53 const int num_sides = DEFAULT_ELLIPSE_POINTS);
54
55 VisualObject(const mrs_msgs::msg::Path& p, const double r, const double g, const double b, const double a, const rclcpp::Duration& timeout,
56 const bool filled, const unsigned long& id, const rclcpp::Node::SharedPtr& node);
57
58 VisualObject(const mrs_msgs::msg::TrajectoryReference& traj, const double r, const double g, const double b, const double a,
59 const rclcpp::Duration& timeout, const bool filled, const unsigned long& id, const rclcpp::Node::SharedPtr& node);
60
61
62 public:
63 unsigned long getID() const;
64 int getType() const;
65 bool isTimedOut() const;
66
67 const std::vector<geometry_msgs::msg::Point> getPoints() const;
68 const std::vector<std_msgs::msg::ColorRGBA> getColors() const;
69
70 bool operator<(const VisualObject& other) const
71 {
72 return id_ < other.id_;
73 }
74
75 bool operator>(const VisualObject& other) const
76 {
77 return id_ > other.id_;
78 }
79
80 bool operator==(const VisualObject& other) const
81 {
82 return id_ == other.id_;
83 }
84
85 private:
86 const unsigned long id_;
87 MarkerType type_;
88 std::vector<geometry_msgs::msg::Point> points_;
89 std::vector<std_msgs::msg::ColorRGBA> colors_;
90 rclcpp::Time timeout_time_;
91 rclcpp::Node::SharedPtr node_;
92
93 void addRay(const mrs_lib::geometry::Ray& ray, const double r, const double g, const double b, const double a);
94
95 void addTriangle(const mrs_lib::geometry::Triangle& triangle, const double r, const double g, const double b, const double a, const bool filled);
96
97 void addEllipse(const mrs_lib::geometry::Ellipse& ellipse, const double r, const double g, const double b, const double a, const bool filled,
98 const int num_points);
99
100 }; // namespace batch_visualizer
101
102} // namespace mrs_lib
103
104#endif
Definition visual_object.h:25
geometric representaiton of a cone
Definition shapes.h:575
geometric representation of a cuboid
Definition shapes.h:319
geometric representation of a cylinder
Definition shapes.h:492
geometric representation of an ellipse
Definition shapes.h:428
geometric representation of a ray. Instantiate it by two input Vector3. Use static methods for from-t...
Definition shapes.h:26
geometric representation of a rectangle (can represent any quadrilateral)
Definition shapes.h:189
geometric representation of a triangle. Instantiate a new triangle by providing three vertices
Definition shapes.h:100
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Defines various geometrical shapes and their relations.