Classes | Typedefs | Enumerations | Functions
hebi::robot_model Namespace Reference

Classes

class  ActuatorMetadata
 Actuator specific view of an element in a RobotModel instance. More...
 
class  BracketMetadata
 Bracket specific view of an element in a RobotModel instance. More...
 
class  CustomObjective
 Allows you to add a custom objective function. More...
 
class  EndEffectorPositionObjective
 
class  EndEffectorSO3Objective
 
class  EndEffectorTipAxisObjective
 
struct  IKResult
 
class  JointLimitConstraint
 
class  JointMetadata
 Joint specific view of an element in a RobotModel instance. More...
 
class  LinkMetadata
 Link specific view of an element in a RobotModel instance. More...
 
class  MetadataBase
 Base class for all metadata. Do not instantiate directly. More...
 
class  Objective
 
class  RigidBodyMetadata
 Rigid Body specific view of an element in a RobotModel instance. More...
 
class  RobotModel
 Represents a chain or tree of robot elements (rigid bodies and joints). More...
 

Typedefs

using Matrix4dVector = std::vector< Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d >>
 
using MatrixXdVector = std::vector< MatrixXd, Eigen::aligned_allocator< Eigen::MatrixXd >>
 

Enumerations

enum  ActuatorType {
  ActuatorType::X5_1 = HebiActuatorTypeX5_1, ActuatorType::X5_4 = HebiActuatorTypeX5_4, ActuatorType::X5_9 = HebiActuatorTypeX5_9, ActuatorType::X8_3 = HebiActuatorTypeX8_3,
  ActuatorType::X8_9 = HebiActuatorTypeX8_9, ActuatorType::X8_16 = HebiActuatorTypeX8_16, ActuatorType::R8_3 = HebiActuatorTypeR8_3, ActuatorType::R8_9 = HebiActuatorTypeR8_9,
  ActuatorType::R8_16 = HebiActuatorTypeR8_16
}
 
enum  BracketType {
  BracketType::X5LightLeft = HebiBracketTypeX5LightLeft, BracketType::X5LightRight = HebiBracketTypeX5LightRight, BracketType::X5HeavyLeftInside = HebiBracketTypeX5HeavyLeftInside, BracketType::X5HeavyLeftOutside = HebiBracketTypeX5HeavyLeftOutside,
  BracketType::X5HeavyRightInside = HebiBracketTypeX5HeavyRightInside, BracketType::X5HeavyRightOutside = HebiBracketTypeX5HeavyRightOutside, BracketType::R8LightLeft = HebiBracketTypeR8LightLeft, BracketType::R8LightRight = HebiBracketTypeR8LightRight,
  BracketType::R8HeavyLeftInside = HebiBracketTypeR8HeavyLeftInside, BracketType::R8HeavyLeftOutside = HebiBracketTypeR8HeavyLeftOutside, BracketType::R8HeavyRightInside = HebiBracketTypeR8HeavyRightInside, BracketType::R8HeavyRightOutside = HebiBracketTypeR8HeavyRightOutside
}
 
enum  ElementType {
  ElementType::Other = HebiRobotModelElementTypeOther, ElementType::Actuator = HebiRobotModelElementTypeActuator, ElementType::Bracket = HebiRobotModelElementTypeBracket, ElementType::Joint = HebiRobotModelElementTypeJoint,
  ElementType::Link = HebiRobotModelElementTypeLink, ElementType::RigidBody = HebiRobotModelElementTypeRigidBody, ElementType::EndEffector = HebiRobotModelElementTypeEndEffector
}
 
enum  EndEffectorType { EndEffectorType::Custom = HebiEndEffectorTypeCustom, EndEffectorType::X5Parallel = HebiEndEffectorTypeX5Parallel, EndEffectorType::R8Parallel = HebiEndEffectorTypeR8Parallel }
 
enum  FrameType { FrameType::CenterOfMass = HebiFrameTypeCenterOfMass, FrameType::Output = HebiFrameTypeOutput, FrameType::EndEffector = HebiFrameTypeEndEffector, FrameType::Input = HebiFrameTypeInput }
 
enum  JointType {
  JointType::RotationX = HebiJointTypeRotationX, JointType::RotationY = HebiJointTypeRotationY, JointType::RotationZ = HebiJointTypeRotationZ, JointType::TranslationX = HebiJointTypeTranslationX,
  JointType::TranslationY = HebiJointTypeTranslationY, JointType::TranslationZ = HebiJointTypeTranslationZ
}
 
enum  LinkInputType { LinkInputType::RightAngle = HebiLinkInputTypeRightAngle, LinkInputType::Inline = HebiLinkInputTypeInline }
 
enum  LinkOutputType { LinkOutputType::RightAngle = HebiLinkOutputTypeRightAngle, LinkOutputType::Inline = HebiLinkOutputTypeInline }
 
enum  LinkType { LinkType::X5 = HebiLinkTypeX5, LinkType::X8 = HebiLinkTypeR8 }
 

Functions

template<size_t T>
void custom_objective_callback_wrapper (void *user_data, size_t num_positions, const double *positions, double *errors)
 C-style callback wrapper to call into CustomObjective class; this should only be used by the CustomObjective class itself. More...
 

Typedef Documentation

using hebi::robot_model::Matrix4dVector = typedef std::vector<Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>

Definition at line 16 of file robot_model.hpp.

using hebi::robot_model::MatrixXdVector = typedef std::vector<MatrixXd, Eigen::aligned_allocator<Eigen::MatrixXd>>

Definition at line 17 of file robot_model.hpp.

Enumeration Type Documentation

enum typedef robot_model::ActuatorType hebi::robot_model::RobotModel::hebi::robot_model::ActuatorType
strong
Enumerator
X5_1 
X5_4 
X5_9 
X8_3 
X8_9 
X8_16 
R8_3 
R8_9 
R8_16 

Definition at line 222 of file robot_model.hpp.

enum typedef robot_model::BracketType hebi::robot_model::RobotModel::hebi::robot_model::BracketType
strong
Enumerator
X5LightLeft 
X5LightRight 
X5HeavyLeftInside 
X5HeavyLeftOutside 
X5HeavyRightInside 
X5HeavyRightOutside 
R8LightLeft 
R8LightRight 
R8HeavyLeftInside 
R8HeavyLeftOutside 
R8HeavyRightInside 
R8HeavyRightOutside 

Definition at line 249 of file robot_model.hpp.

Enumerator
Other 
Actuator 
Bracket 
Joint 
Link 
RigidBody 
EndEffector 

Definition at line 196 of file robot_model.hpp.

Enumerator
Custom 
X5Parallel 
R8Parallel 

Definition at line 264 of file robot_model.hpp.

Enumerator
CenterOfMass 
Output 
EndEffector 
Input 

Definition at line 206 of file robot_model.hpp.

Enumerator
RotationX 
RotationY 
RotationZ 
TranslationX 
TranslationY 
TranslationZ 

Definition at line 213 of file robot_model.hpp.

Enumerator
RightAngle 
Inline 

Definition at line 239 of file robot_model.hpp.

Enumerator
RightAngle 
Inline 

Definition at line 244 of file robot_model.hpp.

enum typedef robot_model::LinkType hebi::robot_model::RobotModel::hebi::robot_model::LinkType
strong
Enumerator
X5 
X8 

Definition at line 234 of file robot_model.hpp.

Function Documentation

template<size_t T>
void hebi::robot_model::custom_objective_callback_wrapper ( void *  user_data,
size_t  num_positions,
const double *  positions,
double *  errors 
)
inline

C-style callback wrapper to call into CustomObjective class; this should only be used by the CustomObjective class itself.

INTERNAL This is forward declared here so it can be used in the CustomObjective class below.

INTERNAL

Definition at line 185 of file robot_model.hpp.



hebi_cpp_api_ros
Author(s): Chris Bollinger , Matthew Tesch
autogenerated on Thu May 28 2020 03:14:45