Skip to content

Commit

Permalink
Allow to enable frame locking in the markers/markers arrays (#56)
Browse files Browse the repository at this point in the history
  • Loading branch information
VictorLamoine authored and davetcoleman committed Aug 17, 2017
1 parent 4655a55 commit bb15af0
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 1 deletion.
6 changes: 6 additions & 0 deletions README.md
Expand Up @@ -194,6 +194,12 @@ Convenience functions
- getCenterPoint
- getVectorBetweenPoints

Frame locking

![](resources/frame_locking.gif)

This allows the markers to be automatically updated as the base frame moves without having to republish. You can enable it via ``enableFrameLocking()`` (this is not enabled by default).

### Available Colors

This package helps you quickly choose colors - feel free to send PRs with more colors as needed
Expand Down
8 changes: 7 additions & 1 deletion include/rviz_visual_tools/rviz_visual_tools.h
Expand Up @@ -369,6 +369,12 @@ class RvizVisualTools
*/
void enableBatchPublishing(bool enable = true);

/**
* \brief Enable frame locking - useful for when the markers is attached to a moving TF, the marker will be
* re-transformed into its frame every time-step
*/
void enableFrameLocking(bool enable = true);

/**
* \brief Trigger the publish function to send out all collected markers IF there are at leats
* queueSize number of markers ready to be published.
Expand Down Expand Up @@ -1080,7 +1086,7 @@ a * Warning: when using this in a loop be sure to call trigger() at end

// Settings
bool batch_publishing_enabled_ = true;
;
bool frame_locking_enabled_ = false;
double alpha_; // opacity of all markers
double global_scale_; // allow all markers to be increased by a constanct factor

Expand Down
Binary file added resources/frame_locking.gif
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
6 changes: 6 additions & 0 deletions src/rviz_visual_tools.cpp
Expand Up @@ -831,6 +831,7 @@ Eigen::Affine3d RvizVisualTools::getVectorBetweenPoints(const Eigen::Vector3d &a
bool RvizVisualTools::publishMarker(visualization_msgs::Marker &marker)
{
// Add single marker to array
marker.frame_locked = frame_locking_enabled_;
markers_.markers.push_back(marker);

// Determine if we should publish now
Expand All @@ -847,6 +848,11 @@ void RvizVisualTools::enableBatchPublishing(bool enable)
batch_publishing_enabled_ = enable;
}

void RvizVisualTools::enableFrameLocking(bool enable)
{
frame_locking_enabled_ = enable;
}

bool RvizVisualTools::triggerEvery(std::size_t queueSize)
{
if (markers_.markers.size() >= queueSize || queueSize == 0)
Expand Down

0 comments on commit bb15af0

Please sign in to comment.