Skip to content

Commit

Permalink
toggle visualizations on and off
Browse files Browse the repository at this point in the history
  • Loading branch information
remod committed Mar 17, 2015
1 parent e21a655 commit 8ba8b48
Show file tree
Hide file tree
Showing 6 changed files with 438 additions and 167 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,13 @@ Q_OBJECT


private Q_SLOTS:
void setShowConnection();
void setShowTransformRotation();
void setShowVelocityLinear();
void setShowVelocityAngular();
void setShowAccelerationLinear();
void setShowAccelerationAngular();

void setSizeTransformRotation();
void setDiameterArrows();
void setScaleVelocityLinear();
Expand All @@ -65,6 +72,13 @@ private Q_SLOTS:
private:
void processMessage(const trajectory_msgs::MultiDOFJointTrajectory::ConstPtr& msg);

void updateShowConnection();
void updateShowTransformRotation();
void updateShowVelocityLinear();
void updateShowVelocityAngular();
void updateShowAccelerationLinear();
void updateShowAccelerationAngular();

void updateSizeTransformRotation();
void updateDiameterArrows();
void updateScaleVelocityLinear();
Expand All @@ -82,28 +96,42 @@ private Q_SLOTS:
void updateFontSize();
void updateShowText();

boost::circular_buffer<std::vector<boost::shared_ptr<MultiDOFJointTrajectoryPointVisual>>> points_visuals_;
boost::circular_buffer<std::vector<boost::shared_ptr<MultiDOFJointTrajectoryPointConnectionVisual>>> connections_visuals_;

rviz::FloatProperty* size_property_transform_rotation_;
rviz::FloatProperty* diameter_property_arrows_;
rviz::FloatProperty* scale_property_velocity_linear_;
rviz::FloatProperty* scale_property_velocity_angular_;
rviz::FloatProperty* scale_property_acceleration_linear_;
rviz::FloatProperty* scale_property_acceleration_angular_;

rviz::ColorProperty* color_property_connection_;
rviz::ColorProperty* color_property_velocity_linear_;
rviz::ColorProperty* color_property_velocity_angular_;
rviz::ColorProperty* color_property_acceleration_linear_;
rviz::ColorProperty* color_property_acceleration_angular_;

rviz::FloatProperty* alpha_property_;

rviz::FloatProperty* font_size_property_;
rviz::BoolProperty* show_text_property_;

rviz::IntProperty* history_length_property_;
boost::circular_buffer<std::vector<boost::shared_ptr<MultiDOFJointTrajectoryPointVisual>>> visuals_points_;
boost::circular_buffer<std::vector<boost::shared_ptr<MultiDOFJointTrajectoryPointConnectionVisual>>> visuals_connections_;

rviz::BoolProperty* property_show_connection_;
rviz::BoolProperty* property_show_transform_rotation_;
rviz::BoolProperty* property_show_velocity_linear_;
rviz::BoolProperty* property_show_velocity_angular_;
rviz::BoolProperty* property_show_acceleration_linear_;
rviz::BoolProperty* property_show_acceleration_angular_;

rviz::FloatProperty* property_size_transform_rotation_;
rviz::FloatProperty* property_diameter_arrows_;
rviz::FloatProperty* property_scale_velocity_linear_;
rviz::FloatProperty* property_scale_velocity_angular_;
rviz::FloatProperty* property_scale_acceleration_linear_;
rviz::FloatProperty* property_scale_acceleration_angular_;

rviz::ColorProperty* property_color_connection_;
rviz::ColorProperty* property_color_velocity_linear_;
rviz::ColorProperty* property_color_velocity_angular_;
rviz::ColorProperty* property_color_acceleration_linear_;
rviz::ColorProperty* property_color_acceleration_angular_;

rviz::FloatProperty* property_alpha_;

rviz::FloatProperty* property_font_size_;
rviz::BoolProperty* property_show_text_;

rviz::IntProperty* property_history_length_;

bool show_connection_;
bool show_transform_rotation_;
bool show_velocity_linear_;
bool show_velocity_angular_;
bool show_acceleration_linear_;
bool show_acceleration_angular_;

float size_transform_rotation_;
float diameter_arrows_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,15 @@ class MultiDOFJointTrajectoryPointConnectionVisual
Ogre::SceneNode* parent_node,
const trajectory_msgs::MultiDOFJointTrajectoryPoint& from,
const trajectory_msgs::MultiDOFJointTrajectoryPoint& to,
float show_connection,
const Ogre::ColourValue& color);
virtual ~MultiDOFJointTrajectoryPointConnectionVisual();

void setShowConnection(bool visible);
void setColor(const Ogre::ColourValue& color);

private:
void updateShowConnection();
void updateColor();

Ogre::SceneManager* scene_manager_;
Expand All @@ -36,6 +39,7 @@ class MultiDOFJointTrajectoryPointConnectionVisual

std::vector<boost::shared_ptr<rviz::Line>> lines_;

float show_connection_;
Ogre::ColourValue color_;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@ class MultiDOFJointTrajectoryPointVisual
Ogre::SceneManager* scene_manager,
Ogre::SceneNode* parent_node,
const trajectory_msgs::MultiDOFJointTrajectoryPoint& msg,
bool show_transform_rotation,
bool show_velocity_linear,
bool show_velocity_angular,
bool show_acceleration_linear,
bool show_acceleration_angular,
float size_transform_rotation,
float diameter_arrows,
float scale_velocity_linear,
Expand All @@ -40,6 +45,12 @@ class MultiDOFJointTrajectoryPointVisual
bool show_text);
virtual ~MultiDOFJointTrajectoryPointVisual();

void setShowTransformRotation(bool visible);
void setShowVelocityLinear(bool visible);
void setShowVelocityAngular(bool visible);
void setShowAccelerationLinear(bool visible);
void setShowAccelerationAngular(bool visible);

void setSizeTransformRotation(float size);
void setDiametersArrows(float diameter);
void setScaleVelocityLinear(float scale);
Expand Down Expand Up @@ -76,6 +87,7 @@ class MultiDOFJointTrajectoryPointVisual
void updateFontSize();
void updateShowText();

Ogre::ColourValue getColor(const Ogre::ColourValue& color, bool visible);
float getCharacterHeight();

Ogre::SceneManager* scene_manager_;
Expand All @@ -93,6 +105,12 @@ class MultiDOFJointTrajectoryPointVisual
std::vector<double> accelerations_linear_absolute_;
std::vector<double> accelerations_angular_absolute_;

bool show_transform_rotation_;
bool show_velocity_linear_;
bool show_velocity_angular_;
bool show_acceleration_linear_;
bool show_acceleration_angular_;

const float axis_radius_per_size_;

float size_transform_rotation_;
Expand Down
Loading

0 comments on commit 8ba8b48

Please sign in to comment.