Classes | Namespaces | Typedefs | Enumerations | Functions
robot_model.hpp File Reference
#include "hebi.h"
#include <memory>
#include <vector>
#include "Eigen/Eigen"
#include "util.hpp"
Include dependency graph for robot_model.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

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

Namespaces

 hebi
 
 hebi::robot_model
 

Typedefs

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

Enumerations

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

Functions

template<size_t T>
void hebi::robot_model::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...
 


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