Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
xpp::RvizRobotBuilder Class Reference

Constructs RVIZ markers that visualize a Cartesian robot state. More...

#include <rviz_robot_builder.h>

List of all members.

Public Member Functions

MarkerArray BuildRobotState (const xpp_msgs::RobotStateCartesian &msg) const
 Constructs the RVIZ markers from the ROS message.
 RvizRobotBuilder ()
 Builds an uninitialized visualizer.
void SetRobotParameters (const xpp_msgs::RobotParameters &msg)
 Provides additional robot info that can be used for visualization.
void SetTerrainParameters (const xpp_msgs::TerrainInfo &msg)
 Additional information that can be used for visualization.
virtual ~RvizRobotBuilder ()

Private Member Functions

Marker CreateBasePose (const Vector3d &pos, Eigen::Quaterniond ori, const ContactState &c) const
Marker CreateBox (const Vector3d &pos, Eigen::Quaterniond ori, const Vector3d &edge_length) const
Marker CreateCopPos (const EEForces &f_W, const EEPos &pos_W) const
MarkerVec CreateEEForces (const EEForces &f_W, const EEPos &pos_W, const ContactState &c) const
MarkerVec CreateEEPositions (const EEPos &pos_W, const ContactState &c) const
Marker CreateForceArrow (const Vector3d &f, const Vector3d &pos) const
Marker CreateFrictionCone (const Vector3d &pos_W, const Vector3d &terrain_normal, double friction_coeff) const
MarkerVec CreateFrictionCones (const EEPos &pos_W, const ContactState &c) const
Marker CreateGravityForce (const Vector3d &base_pos) const
Marker CreatePendulum (const Vector3d &base_pos, const EEForces &f_W, const EEPos &pos_W) const
MarkerVec CreateRangeOfMotion (const State3d &base) const
Marker CreateSphere (const Vector3d &pos, double diameter=0.03) const
MarkerVec CreateSupportArea (const ContactState &c, const EEPos &pos_W) const
void FillWithInvisible (int max_size, MarkerVec &vec) const

Private Attributes

const std::string frame_id_ = "world"
xpp_msgs::RobotParameters params_msg_
xpp_msgs::TerrainInfo terrain_msg_

Static Private Attributes

static const int max_ee_ = 10

Detailed Description

Constructs RVIZ markers that visualize a Cartesian robot state.

This class is responsible for converting robot states into beautiful RVIZ markers. The visualize quantities such as 6D base state, endeffector positions, contact state of these, endeffector forces, support areas and center of pressure.

Definition at line 56 of file rviz_robot_builder.h.


Constructor & Destructor Documentation

Builds an uninitialized visualizer.

Definition at line 37 of file rviz_robot_builder.cc.


Member Function Documentation

RvizRobotBuilder::MarkerArray xpp::RvizRobotBuilder::BuildRobotState ( const xpp_msgs::RobotStateCartesian &  msg) const

Constructs the RVIZ markers from the ROS message.

Parameters:
msgThe ROS message describing the Cartesian robot state.
Returns:
The array of RVIZ markers to be published.

Definition at line 63 of file rviz_robot_builder.cc.

RvizRobotBuilder::Marker xpp::RvizRobotBuilder::CreateBasePose ( const Vector3d &  pos,
Eigen::Quaterniond  ori,
const ContactState &  c 
) const [private]

Definition at line 216 of file rviz_robot_builder.cc.

RvizRobotBuilder::Marker xpp::RvizRobotBuilder::CreateBox ( const Vector3d &  pos,
Eigen::Quaterniond  ori,
const Vector3d &  edge_length 
) const [private]

Definition at line 311 of file rviz_robot_builder.cc.

RvizRobotBuilder::Marker xpp::RvizRobotBuilder::CreateCopPos ( const EEForces &  f_W,
const EEPos &  pos_W 
) const [private]

Definition at line 235 of file rviz_robot_builder.cc.

RvizRobotBuilder::MarkerVec xpp::RvizRobotBuilder::CreateEEForces ( const EEForces &  f_W,
const EEPos &  pos_W,
const ContactState &  c 
) const [private]

Definition at line 142 of file rviz_robot_builder.cc.

RvizRobotBuilder::MarkerVec xpp::RvizRobotBuilder::CreateEEPositions ( const EEPos &  pos_W,
const ContactState &  c 
) const [private]

Definition at line 113 of file rviz_robot_builder.cc.

RvizRobotBuilder::Marker xpp::RvizRobotBuilder::CreateForceArrow ( const Vector3d &  f,
const Vector3d &  pos 
) const [private]

Definition at line 339 of file rviz_robot_builder.cc.

RvizRobotBuilder::Marker xpp::RvizRobotBuilder::CreateFrictionCone ( const Vector3d &  pos_W,
const Vector3d &  terrain_normal,
double  friction_coeff 
) const [private]

Definition at line 192 of file rviz_robot_builder.cc.

RvizRobotBuilder::MarkerVec xpp::RvizRobotBuilder::CreateFrictionCones ( const EEPos &  pos_W,
const ContactState &  c 
) const [private]

Definition at line 163 of file rviz_robot_builder.cc.

RvizRobotBuilder::Marker xpp::RvizRobotBuilder::CreateGravityForce ( const Vector3d &  base_pos) const [private]

Definition at line 130 of file rviz_robot_builder.cc.

RvizRobotBuilder::Marker xpp::RvizRobotBuilder::CreatePendulum ( const Vector3d &  base_pos,
const EEForces &  f_W,
const EEPos &  pos_W 
) const [private]

Definition at line 262 of file rviz_robot_builder.cc.

RvizRobotBuilder::MarkerVec xpp::RvizRobotBuilder::CreateRangeOfMotion ( const State3d base) const [private]

Definition at line 290 of file rviz_robot_builder.cc.

RvizRobotBuilder::Marker xpp::RvizRobotBuilder::CreateSphere ( const Vector3d &  pos,
double  diameter = 0.03 
) const [private]

Definition at line 325 of file rviz_robot_builder.cc.

RvizRobotBuilder::MarkerVec xpp::RvizRobotBuilder::CreateSupportArea ( const ContactState &  c,
const EEPos &  pos_W 
) const [private]

Definition at line 361 of file rviz_robot_builder.cc.

void xpp::RvizRobotBuilder::FillWithInvisible ( int  max_size,
MarkerVec &  vec 
) const [private]

Makes sure no artifacts remain from previous visualization.

Parameters:
max_sizeNumber of marker for this rviz vector, should be constant.
vecThe vector of rviz markers.

Definition at line 55 of file rviz_robot_builder.cc.

void xpp::RvizRobotBuilder::SetRobotParameters ( const xpp_msgs::RobotParameters &  msg)

Provides additional robot info that can be used for visualization.

Parameters:
msgThe ROS message.

This additional information includes such values as the robots mass (for gravity force visualization), the robots nominal endeffector configuration, etc (see OptParameters).

Definition at line 43 of file rviz_robot_builder.cc.

void xpp::RvizRobotBuilder::SetTerrainParameters ( const xpp_msgs::TerrainInfo &  msg)

Additional information that can be used for visualization.

Parameters:
msgThe ROS message.

This information is related to the terrain, such as the current terrain normals at the endeffectors and friction coefficient (for friction cone visualization).

Definition at line 49 of file rviz_robot_builder.cc.


Member Data Documentation

const std::string xpp::RvizRobotBuilder::frame_id_ = "world" [private]

Definition at line 140 of file rviz_robot_builder.h.

const int xpp::RvizRobotBuilder::max_ee_ = 10 [static, private]

Definition at line 148 of file rviz_robot_builder.h.

xpp_msgs::RobotParameters xpp::RvizRobotBuilder::params_msg_ [private]

Definition at line 137 of file rviz_robot_builder.h.

xpp_msgs::TerrainInfo xpp::RvizRobotBuilder::terrain_msg_ [private]

Definition at line 138 of file rviz_robot_builder.h.


The documentation for this class was generated from the following files:


xpp_vis
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 5 2019 02:55:52