SMACC2
|
#include <cp_waypoints_visualizer.hpp>
Public Member Functions | |
CpWaypointsVisualizer (rclcpp::Duration duration) | |
void | onInitialize () override |
Public Member Functions inherited from smacc2::ISmaccComponent | |
ISmaccComponent () | |
virtual | ~ISmaccComponent () |
virtual std::string | getName () const |
Public Member Functions inherited from smacc2::ISmaccUpdatable | |
ISmaccUpdatable () | |
ISmaccUpdatable (rclcpp::Duration duration) | |
void | executeUpdate (rclcpp::Node::SharedPtr node) |
void | setUpdatePeriod (rclcpp::Duration duration) |
Public Attributes | |
cl_nitrosz::CpWaypointNavigator * | waypointsNavigator_ |
Private Member Functions | |
void | createMarker (const geometry_msgs::msg::Pose &waypoint, visualization_msgs::msg::Marker &m) |
void | createMarkerLabel (const geometry_msgs::msg::Pose &waypoint, std::string label, visualization_msgs::msg::Marker &m) |
Private Attributes | |
std::mutex | m_mutex_ |
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr | markersPub_ |
visualization_msgs::msg::MarkerArray | markers_ |
visualization_msgs::msg::MarkerArray | markerLabels_ |
Additional Inherited Members | |
Protected Attributes inherited from smacc2::ISmaccComponent | |
ISmaccStateMachine * | stateMachine_ |
ISmaccClient * | owner_ |
Definition at line 34 of file cp_waypoints_visualizer.hpp.
cl_nitrosz::CpWaypointsVisualizer::CpWaypointsVisualizer | ( | rclcpp::Duration | duration | ) |
Definition at line 27 of file cp_waypoints_visualizer.cpp.
|
private |
Definition at line 86 of file cp_waypoints_visualizer.cpp.
References cl_nitrosz::frameid, smacc2::ISmaccComponent::getNode(), and markers_.
Referenced by onInitialize().
|
private |
Definition at line 65 of file cp_waypoints_visualizer.cpp.
References cl_nitrosz::frameid, smacc2::ISmaccComponent::getNode(), and markers_.
Referenced by onInitialize().
|
overridevirtual |
Reimplemented from smacc2::ISmaccComponent.
Definition at line 31 of file cp_waypoints_visualizer.cpp.
References createMarker(), createMarkerLabel(), smacc2::ISmaccComponent::getNode(), cl_nitrosz::CpWaypointNavigatorBase::getWaypointNames(), cl_nitrosz::CpWaypointNavigatorBase::getWaypoints(), markerLabels_, markers_, markersPub_, smacc2::ISmaccComponent::requiresComponent(), and waypointsNavigator_.
|
overrideprotectedvirtual |
Implements smacc2::ISmaccUpdatable.
Definition at line 104 of file cp_waypoints_visualizer.cpp.
References cl_nitrosz::CpWaypointNavigatorBase::getCurrentWaypointIndex(), smacc2::ISmaccComponent::getNode(), m_mutex_, markerLabels_, markers_, markersPub_, and waypointsNavigator_.
|
private |
Definition at line 47 of file cp_waypoints_visualizer.hpp.
Referenced by update().
|
private |
Definition at line 51 of file cp_waypoints_visualizer.hpp.
Referenced by onInitialize(), and update().
|
private |
Definition at line 50 of file cp_waypoints_visualizer.hpp.
Referenced by createMarker(), createMarkerLabel(), onInitialize(), and update().
|
private |
Definition at line 49 of file cp_waypoints_visualizer.hpp.
Referenced by onInitialize(), and update().
cl_nitrosz::CpWaypointNavigator* cl_nitrosz::CpWaypointsVisualizer::waypointsNavigator_ |
Definition at line 37 of file cp_waypoints_visualizer.hpp.
Referenced by onInitialize(), and update().