Public Member Functions | Protected Attributes | Private Slots | Private Member Functions | Private Attributes | List of all members
rviz::RobotJoint Struct Reference

Contains any data we need from a joint in the robot. More...

#include <robot_joint.h>

Inheritance diagram for rviz::RobotJoint:
Inheritance graph
[legend]

Public Member Functions

void calculateJointCheckboxesRecursive (int &links_with_geom, int &links_with_geom_checked, int &links_with_geom_unchecked)
 
void expandDetails (bool expand)
 
const std::string & getChildLinkName () const
 
const PropertygetJointProperty () const
 
PropertygetJointProperty ()
 
const std::string & getName () const
 
Ogre::Quaternion getOrientation ()
 
RobotJointgetParentJoint ()
 
const std::string & getParentLinkName () const
 
Ogre::Vector3 getPosition ()
 
bool hasDescendentLinksWithGeometry () const
 
void hideSubProperties (bool hide)
 
 RobotJoint (Robot *robot, const urdf::JointConstSharedPtr &joint)
 
void setJointPropertyDescription ()
 
void setParentProperty (Property *new_parent)
 
void setRobotAlpha (float)
 
void setTransforms (const Ogre::Vector3 &parent_link_position, const Ogre::Quaternion &parent_link_orientation)
 
void useDetailProperty (bool use_detail)
 
 ~RobotJoint () override
 

Protected Attributes

Propertyaxes_property_
 
VectorPropertyaxis_property_
 
std::string child_link_name_
 
Propertydetails_
 
Propertyjoint_property_
 
FloatPropertylower_limit_property_
 
std::string name_
 Name of this joint. More...
 
QuaternionPropertyorientation_property_
 
std::string parent_link_name_
 
VectorPropertyposition_property_
 
Robotrobot_
 
Propertyshow_axis_property_
 
StringPropertytype_property_
 
FloatPropertyupper_limit_property_
 

Private Slots

void updateAxes ()
 
void updateAxis ()
 
void updateChildVisibility ()
 

Private Member Functions

void getChildLinkState (int &links_with_geom, int &links_with_geom_checked, int &links_with_geom_unchecked, bool recursive) const
 
bool getEnabled () const
 
void setJointCheckbox (QVariant val)
 
bool styleIsTree () const
 

Private Attributes

Axesaxes_
 
Arrowaxis_
 
bool doing_set_checkbox_
 
bool has_decendent_links_with_geometry_
 
Ogre::Vector3 joint_origin_pos_
 
Ogre::Quaternion joint_origin_rot_
 

Detailed Description

Contains any data we need from a joint in the robot.

Definition at line 84 of file robot_joint.h.

Constructor & Destructor Documentation

◆ RobotJoint()

rviz::RobotJoint::RobotJoint ( Robot robot,
const urdf::JointConstSharedPtr &  joint 
)

Definition at line 46 of file robot_joint.cpp.

◆ ~RobotJoint()

rviz::RobotJoint::~RobotJoint ( )
override

Definition at line 131 of file robot_joint.cpp.

Member Function Documentation

◆ calculateJointCheckboxesRecursive()

void rviz::RobotJoint::calculateJointCheckboxesRecursive ( int &  links_with_geom,
int &  links_with_geom_checked,
int &  links_with_geom_unchecked 
)

Definition at line 205 of file robot_joint.cpp.

◆ expandDetails()

void rviz::RobotJoint::expandDetails ( bool  expand)

Definition at line 490 of file robot_joint.cpp.

◆ getChildLinkName()

const std::string& rviz::RobotJoint::getChildLinkName ( ) const
inline

Definition at line 103 of file robot_joint.h.

◆ getChildLinkState()

void rviz::RobotJoint::getChildLinkState ( int &  links_with_geom,
int &  links_with_geom_checked,
int &  links_with_geom_unchecked,
bool  recursive 
) const
private

Definition at line 265 of file robot_joint.cpp.

◆ getEnabled()

bool rviz::RobotJoint::getEnabled ( ) const
private

Definition at line 305 of file robot_joint.cpp.

◆ getJointProperty() [1/2]

const Property* rviz::RobotJoint::getJointProperty ( ) const
inline

Definition at line 107 of file robot_joint.h.

◆ getJointProperty() [2/2]

Property* rviz::RobotJoint::getJointProperty ( )
inline

Definition at line 111 of file robot_joint.h.

◆ getName()

const std::string& rviz::RobotJoint::getName ( ) const
inline

Definition at line 95 of file robot_joint.h.

◆ getOrientation()

Ogre::Quaternion rviz::RobotJoint::getOrientation ( )

Definition at line 441 of file robot_joint.cpp.

◆ getParentJoint()

RobotJoint * rviz::RobotJoint::getParentJoint ( )

Definition at line 192 of file robot_joint.cpp.

◆ getParentLinkName()

const std::string& rviz::RobotJoint::getParentLinkName ( ) const
inline

Definition at line 99 of file robot_joint.h.

◆ getPosition()

Ogre::Vector3 rviz::RobotJoint::getPosition ( )

Definition at line 436 of file robot_joint.cpp.

◆ hasDescendentLinksWithGeometry()

bool rviz::RobotJoint::hasDescendentLinksWithGeometry ( ) const
inline

Definition at line 129 of file robot_joint.h.

◆ hideSubProperties()

void rviz::RobotJoint::hideSubProperties ( bool  hide)

Definition at line 427 of file robot_joint.cpp.

◆ setJointCheckbox()

void rviz::RobotJoint::setJointCheckbox ( QVariant  val)
private

Definition at line 183 of file robot_joint.cpp.

◆ setJointPropertyDescription()

void rviz::RobotJoint::setJointPropertyDescription ( )

Definition at line 140 of file robot_joint.cpp.

◆ setParentProperty()

void rviz::RobotJoint::setParentProperty ( Property new_parent)

Definition at line 446 of file robot_joint.cpp.

◆ setRobotAlpha()

void rviz::RobotJoint::setRobotAlpha ( float  )
inline

Definition at line 125 of file robot_joint.h.

◆ setTransforms()

void rviz::RobotJoint::setTransforms ( const Ogre::Vector3 &  parent_link_position,
const Ogre::Quaternion &  parent_link_orientation 
)

Definition at line 406 of file robot_joint.cpp.

◆ styleIsTree()

bool rviz::RobotJoint::styleIsTree ( ) const
private

Definition at line 312 of file robot_joint.cpp.

◆ updateAxes

void rviz::RobotJoint::updateAxes ( )
privateslot

Definition at line 351 of file robot_joint.cpp.

◆ updateAxis

void rviz::RobotJoint::updateAxis ( )
privateslot

Definition at line 377 of file robot_joint.cpp.

◆ updateChildVisibility

void rviz::RobotJoint::updateChildVisibility ( )
privateslot

Definition at line 317 of file robot_joint.cpp.

◆ useDetailProperty()

void rviz::RobotJoint::useDetailProperty ( bool  use_detail)

Definition at line 462 of file robot_joint.cpp.

Member Data Documentation

◆ axes_

Axes* rviz::RobotJoint::axes_
private

Definition at line 202 of file robot_joint.h.

◆ axes_property_

Property* rviz::RobotJoint::axes_property_
protected

Definition at line 187 of file robot_joint.h.

◆ axis_

Arrow* rviz::RobotJoint::axis_
private

Definition at line 203 of file robot_joint.h.

◆ axis_property_

VectorProperty* rviz::RobotJoint::axis_property_
protected

Definition at line 189 of file robot_joint.h.

◆ child_link_name_

std::string rviz::RobotJoint::child_link_name_
protected

Definition at line 180 of file robot_joint.h.

◆ details_

Property* rviz::RobotJoint::details_
protected

Definition at line 184 of file robot_joint.h.

◆ doing_set_checkbox_

bool rviz::RobotJoint::doing_set_checkbox_
private

Definition at line 200 of file robot_joint.h.

◆ has_decendent_links_with_geometry_

bool rviz::RobotJoint::has_decendent_links_with_geometry_
private

Definition at line 198 of file robot_joint.h.

◆ joint_origin_pos_

Ogre::Vector3 rviz::RobotJoint::joint_origin_pos_
private

Definition at line 196 of file robot_joint.h.

◆ joint_origin_rot_

Ogre::Quaternion rviz::RobotJoint::joint_origin_rot_
private

Definition at line 197 of file robot_joint.h.

◆ joint_property_

Property* rviz::RobotJoint::joint_property_
protected

Definition at line 183 of file robot_joint.h.

◆ lower_limit_property_

FloatProperty* rviz::RobotJoint::lower_limit_property_
protected

Definition at line 192 of file robot_joint.h.

◆ name_

std::string rviz::RobotJoint::name_
protected

Name of this joint.

Definition at line 178 of file robot_joint.h.

◆ orientation_property_

QuaternionProperty* rviz::RobotJoint::orientation_property_
protected

Definition at line 186 of file robot_joint.h.

◆ parent_link_name_

std::string rviz::RobotJoint::parent_link_name_
protected

Definition at line 179 of file robot_joint.h.

◆ position_property_

VectorProperty* rviz::RobotJoint::position_property_
protected

Definition at line 185 of file robot_joint.h.

◆ robot_

Robot* rviz::RobotJoint::robot_
protected

Definition at line 177 of file robot_joint.h.

◆ show_axis_property_

Property* rviz::RobotJoint::show_axis_property_
protected

Definition at line 190 of file robot_joint.h.

◆ type_property_

StringProperty* rviz::RobotJoint::type_property_
protected

Definition at line 191 of file robot_joint.h.

◆ upper_limit_property_

FloatProperty* rviz::RobotJoint::upper_limit_property_
protected

Definition at line 193 of file robot_joint.h.


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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:26