A wrapper class of RViz InteractiveMarker for visualizing AIKIDO trajectory in RViz.
More...
#include <aikido/rviz/TrajectoryMarker.hpp>
A wrapper class of RViz InteractiveMarker for visualizing AIKIDO trajectory in RViz.
◆ TrajectoryMarker()
aikido::rviz::TrajectoryMarker::TrajectoryMarker |
( |
interactive_markers::InteractiveMarkerServer * |
markerServer, |
|
|
const std::string & |
frameId, |
|
|
const std::string & |
markerName, |
|
|
trajectory::ConstTrajectoryPtr |
trajectory, |
|
|
dart::dynamics::MetaSkeletonPtr |
skeleton, |
|
|
const dart::dynamics::Frame & |
frame, |
|
|
const Eigen::Vector4d & |
rgba = Eigen::Vector4d::Constant(0.75) , |
|
|
double |
thickness = 0.01 , |
|
|
std::size_t |
numLineSegments = 16u |
|
) |
| |
Constructor.
- Parameters
-
[in] | markerServer | RViz marker server. |
[in] | frameId | RViz frame ID. |
[in] | markerName | Name of the RViz InteractiveMarker associated with this TrajectoryMarker. The name must be unique in the same InteractiveMarkerServer. AIKIDO InteractiveMarkerViewer uses a name manager for the name uniqueness. |
[in] | trajectory | C-space (or joint-space) trajectory. |
[in] | skeleton | DART meta skeleton for visualizing the trajectory in task space. |
[in] | frame | DART frame for visualizing the trajectory in task space. The trajectory of the origin will be visualized. |
[in] | rgba | Color and alpha of the visualized trajectory. Default is [RGBA: 0.75, 0.75, 0.75, 0.75]. |
[in] | thickness | Thickness of the visualized trajectory. Default is 0.01. |
[in] | numLineSegments | Number of line segments in the visualized trajectory. Default is 16. |
◆ ~TrajectoryMarker()
aikido::rviz::TrajectoryMarker::~TrajectoryMarker |
( |
| ) |
|
◆ getAlpha()
double aikido::rviz::TrajectoryMarker::getAlpha |
( |
| ) |
const |
Returns alpha of visualized trajectory.
◆ getColor()
Eigen::Vector3d aikido::rviz::TrajectoryMarker::getColor |
( |
| ) |
const |
Returns color (RGB) of visualized trajectory.
◆ getMarker() [1/2]
visualization_msgs::Marker& aikido::rviz::TrajectoryMarker::getMarker |
( |
| ) |
|
|
private |
◆ getMarker() [2/2]
const visualization_msgs::Marker& aikido::rviz::TrajectoryMarker::getMarker |
( |
| ) |
const |
|
private |
◆ getNumLineSegments()
std::size_t aikido::rviz::TrajectoryMarker::getNumLineSegments |
( |
| ) |
const |
Returns number of line segments of the visualizing trajectory.
◆ getRBGA()
Eigen::Vector4d aikido::rviz::TrajectoryMarker::getRBGA |
( |
| ) |
const |
Returns RGBA of visualized trajectory.
◆ getThickness()
double aikido::rviz::TrajectoryMarker::getThickness |
( |
| ) |
const |
Returns thickness of visualized trajectory.
◆ getTrajectory()
Returns trajectory associated with this marker.
◆ setAlpha()
void aikido::rviz::TrajectoryMarker::setAlpha |
( |
double |
alpha | ) |
|
Sets or updates alpha of visualized trajectory.
◆ setColor()
void aikido::rviz::TrajectoryMarker::setColor |
( |
const Eigen::Vector3d & |
rgb | ) |
|
Sets or updates color (RGB) of visualized trajectory.
◆ setNumLineSegments()
void aikido::rviz::TrajectoryMarker::setNumLineSegments |
( |
std::size_t |
numLineSegments | ) |
|
Sets or updates number of line segments of the visualizing trajectory.
◆ setRGBA()
void aikido::rviz::TrajectoryMarker::setRGBA |
( |
const Eigen::Vector4d & |
rgb | ) |
|
Sets or updates RGBA of visualized trajectory.
◆ setThickness()
void aikido::rviz::TrajectoryMarker::setThickness |
( |
double |
thickness | ) |
|
Sets or updates thickness of visualized trajectory.
◆ setTrajectory()
Sets or updates trajectory to visualize.
- Parameters
-
[in] | trajectory | C-space (or joint-space) trajectory. The statespace of the trajectory should be MetaSkeletonStateSpace. Otherwise, throws invalid_argument exception. Passing in nullptr will clear the current trajectory. |
◆ update()
void aikido::rviz::TrajectoryMarker::update |
( |
| ) |
|
Updates this marker.
This function should be called after the properties are changed (e.g., trajectory, color, thickness, number of line-segments) so that RViz reflects the changes accordingly.
◆ updatePoints()
void aikido::rviz::TrajectoryMarker::updatePoints |
( |
| ) |
|
|
private |
Updates trajectory points based on trajectory and number of line-segments.
This function is called by update().
◆ mFrame
const dart::dynamics::Frame& aikido::rviz::TrajectoryMarker::mFrame |
|
private |
Target DART frame where the trajectory of its origin will be visualized.
◆ mFrameId
std::string aikido::rviz::TrajectoryMarker::mFrameId |
|
private |
Frame name of RViz interactive marker.
◆ mInteractiveMarker
visualization_msgs::InteractiveMarker aikido::rviz::TrajectoryMarker::mInteractiveMarker |
|
private |
◆ mMarkerServer
interactive_markers::InteractiveMarkerServer* aikido::rviz::TrajectoryMarker::mMarkerServer |
|
private |
◆ mNeedPointsUpdate
bool aikido::rviz::TrajectoryMarker::mNeedPointsUpdate |
|
private |
Whether the trajectory points need to be updated.
◆ mNeedUpdate
bool aikido::rviz::TrajectoryMarker::mNeedUpdate |
|
private |
Whether the associated RViz maker needs to be updated.
◆ mNumLineSegments
std::size_t aikido::rviz::TrajectoryMarker::mNumLineSegments |
|
private |
Number of line segments of the discretized task-space trajectory.
◆ mSkeleton
dart::dynamics::MetaSkeletonPtr aikido::rviz::TrajectoryMarker::mSkeleton |
|
private |
Target DART meta skeleton that the C-space trajectory will be applied to compute the visualizing task-space trajectory.
◆ mTrajectory
C-space (or joint-space) trajectory.