Class CpTrajectoryVisualizer
Defined in File cp_trajectory_visualizer.hpp
Inheritance Relationships
Base Types
public smacc2::ISmaccComponentpublic smacc2::ISmaccUpdatable
Class Documentation
-
class CpTrajectoryVisualizer : public smacc2::ISmaccComponent, public smacc2::ISmaccUpdatable
Component for visualizing trajectories as RViz markers.
This component publishes trajectory paths as visualization markers that can be viewed in RViz. It follows the ISmaccUpdatable pattern for periodic publishing.
Pattern: Publisher + ISmaccUpdatable (similar to nav2z_client’s CpWaypointsVisualizer)
Public Functions
-
inline CpTrajectoryVisualizer(double publishRate = 10.0)
Constructor.
- Parameters:
publishRate – Publishing rate (default: 10Hz)
-
virtual ~CpTrajectoryVisualizer() = default
-
inline void onInitialize() override
Initialize the marker publisher.
-
inline void update() override
Periodic update - publishes markers if enabled.
-
inline void setTrajectory(const std::vector<geometry_msgs::msg::PoseStamped> &poses, const std::string &ns = "trajectory")
Set trajectory to visualize.
- Parameters:
poses – Vector of poses defining the trajectory path
ns – Namespace for the markers (default: “trajectory”)
-
inline void clearMarkers()
Clear all markers.
-
inline void setColor(float r, float g, float b, float a = 1.0)
Set marker color (RGBA values 0.0-1.0)
-
inline void setScale(double scale)
Set marker scale (sphere diameter in meters)
-
inline void setEnabled(bool enabled)
Enable/disable marker publishing.
-
inline bool isEnabled() const
Check if visualizer is enabled.
-
inline CpTrajectoryVisualizer(double publishRate = 10.0)