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);
33 const unsigned long&
id,
const rclcpp::Node::SharedPtr& node);
36 const bool filled,
const unsigned long&
id,
const rclcpp::Node::SharedPtr& node);
39 const bool filled,
const unsigned long&
id,
const rclcpp::Node::SharedPtr& node);
42 const bool filled,
const unsigned long&
id,
const rclcpp::Node::SharedPtr& node);
45 const bool filled,
const unsigned long&
id,
const rclcpp::Node::SharedPtr& node,
const int num_points = DEFAULT_ELLIPSE_POINTS);
48 const bool filled,
const bool capped,
const unsigned long&
id,
const rclcpp::Node::SharedPtr& node,
49 const int num_sides = DEFAULT_ELLIPSE_POINTS);
52 const bool filled,
const bool capped,
const unsigned long&
id,
const rclcpp::Node::SharedPtr& node,
53 const int num_sides = DEFAULT_ELLIPSE_POINTS);
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);
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);
63 unsigned long getID()
const;
65 bool isTimedOut()
const;
67 const std::vector<geometry_msgs::msg::Point> getPoints()
const;
68 const std::vector<std_msgs::msg::ColorRGBA> getColors()
const;
72 return id_ < other.id_;
77 return id_ > other.id_;
82 return id_ == other.id_;
86 const unsigned long id_;
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_;
93 void addRay(
const mrs_lib::geometry::Ray& ray,
const double r,
const double g,
const double b,
const double a);
95 void addTriangle(
const mrs_lib::geometry::Triangle& triangle,
const double r,
const double g,
const double b,
const double a,
const bool filled);
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);
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24