Classes | Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
hebi::experimental::arm::Arm Class Reference

#include <arm.hpp>

Classes

struct  Params
 

Public Member Functions

bool atGoal () const
 
void cancelGoal ()
 
void clearJointLimits (const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
 
const EndEffectorBaseendEffector () const
 
Eigen::Vector3d FK (const Eigen::VectorXd &positions) const
 
void FK (const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
 
void FK (const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const
 
double goalProgress () const
 
const Groupgroup () const
 
const GroupFeedbacklastFeedback () const
 
bool loadGains (const std::string &gains_file)
 
GroupCommandpendingCommand ()
 
const GroupCommandpendingCommand () const
 
const robot_model::RobotModelrobotModel () const
 
bool send ()
 
template<typename T >
void setAuxState (const T &aux_state)
 
void setGoal (const Goal &goal)
 
void setJointLimits (const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
 
size_t size () const
 
Eigen::VectorXd solveIK (const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
 
Eigen::VectorXd solveIK (const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const
 
Eigen::VectorXd solveIK (const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Matrix3d &orientation) const
 
const trajectory::Trajectorytrajectory () const
 
bool update ()
 

Static Public Member Functions

static std::unique_ptr< Armcreate (const Params &params)
 

Private Member Functions

 Arm (std::function< double()> get_current_time_s, std::shared_ptr< Group > group, std::shared_ptr< robot_model::RobotModel > robot_model, std::shared_ptr< EndEffectorBase > end_effector=nullptr)
 
Eigen::VectorXd getAux (double t) const
 

Private Attributes

Eigen::VectorXd accel_
 
Eigen::MatrixXd aux_
 
Eigen::VectorXd aux_times_
 
hebi::GroupCommand command_
 
std::shared_ptr< EndEffectorBaseend_effector_
 
hebi::GroupFeedback feedback_
 
std::function< double()> get_current_time_s_
 
std::shared_ptr< Groupgroup_
 
internal::KinematicsHelper kinematics_helper_
 
double last_time_
 
Eigen::VectorXd masses_
 
Eigen::VectorXd pos_
 
std::shared_ptr< robot_model::RobotModelrobot_model_
 
std::shared_ptr< trajectory::Trajectorytrajectory_
 
double trajectory_start_time_ { std::numeric_limits<double>::quiet_NaN() }
 
Eigen::VectorXd vel_
 

Detailed Description

Definition at line 41 of file arm.hpp.

Constructor & Destructor Documentation

hebi::experimental::arm::Arm::Arm ( std::function< double()>  get_current_time_s,
std::shared_ptr< Group group,
std::shared_ptr< robot_model::RobotModel robot_model,
std::shared_ptr< EndEffectorBase end_effector = nullptr 
)
inlineprivate

Definition at line 269 of file arm.hpp.

Member Function Documentation

bool hebi::experimental::arm::Arm::atGoal ( ) const
inline

Definition at line 205 of file arm.hpp.

void hebi::experimental::arm::Arm::cancelGoal ( )

Definition at line 221 of file arm.cpp.

void hebi::experimental::arm::Arm::clearJointLimits ( const Eigen::VectorXd &  min_positions,
const Eigen::VectorXd &  max_positions 
)
inline

Definition at line 223 of file arm.hpp.

std::unique_ptr< Arm > hebi::experimental::arm::Arm::create ( const Params params)
static

Definition at line 9 of file arm.cpp.

const EndEffectorBase* hebi::experimental::arm::Arm::endEffector ( ) const
inline

Definition at line 110 of file arm.hpp.

Eigen::Vector3d hebi::experimental::arm::Arm::FK ( const Eigen::VectorXd &  positions) const
inline

Definition at line 228 of file arm.hpp.

void hebi::experimental::arm::Arm::FK ( const Eigen::VectorXd &  positions,
Eigen::Vector3d &  xyz_out,
Eigen::Vector3d &  tip_axis 
) const
inline

Definition at line 233 of file arm.hpp.

void hebi::experimental::arm::Arm::FK ( const Eigen::VectorXd &  positions,
Eigen::Vector3d &  xyz_out,
Eigen::Matrix3d &  orientation 
) const
inline

Definition at line 238 of file arm.hpp.

Eigen::VectorXd hebi::experimental::arm::Arm::getAux ( double  t) const
private

Definition at line 226 of file arm.cpp.

double hebi::experimental::arm::Arm::goalProgress ( ) const

Definition at line 211 of file arm.cpp.

const Group& hebi::experimental::arm::Arm::group ( ) const
inline

Definition at line 97 of file arm.hpp.

const GroupFeedback& hebi::experimental::arm::Arm::lastFeedback ( ) const
inline

Definition at line 120 of file arm.hpp.

bool hebi::experimental::arm::Arm::loadGains ( const std::string &  gains_file)

Definition at line 66 of file arm.cpp.

GroupCommand& hebi::experimental::arm::Arm::pendingCommand ( )
inline

Definition at line 115 of file arm.hpp.

const GroupCommand& hebi::experimental::arm::Arm::pendingCommand ( ) const
inline

Definition at line 116 of file arm.hpp.

const robot_model::RobotModel& hebi::experimental::arm::Arm::robotModel ( ) const
inline

Definition at line 100 of file arm.hpp.

bool hebi::experimental::arm::Arm::send ( )

Definition at line 125 of file arm.cpp.

template<typename T >
void hebi::experimental::arm::Arm::setAuxState ( const T &  aux_state)
inline

Definition at line 180 of file arm.hpp.

void hebi::experimental::arm::Arm::setGoal ( const Goal goal)

Definition at line 147 of file arm.cpp.

void hebi::experimental::arm::Arm::setJointLimits ( const Eigen::VectorXd &  min_positions,
const Eigen::VectorXd &  max_positions 
)
inline

Definition at line 217 of file arm.hpp.

size_t hebi::experimental::arm::Arm::size ( ) const
inline

Definition at line 94 of file arm.hpp.

Eigen::VectorXd hebi::experimental::arm::Arm::solveIK ( const Eigen::VectorXd &  initial_positions,
const Eigen::Vector3d &  target_xyz 
) const
inline

Definition at line 243 of file arm.hpp.

Eigen::VectorXd hebi::experimental::arm::Arm::solveIK ( const Eigen::VectorXd &  initial_positions,
const Eigen::Vector3d &  target_xyz,
const Eigen::Vector3d &  end_tip 
) const
inline

Definition at line 251 of file arm.hpp.

Eigen::VectorXd hebi::experimental::arm::Arm::solveIK ( const Eigen::VectorXd &  initial_positions,
const Eigen::Vector3d &  target_xyz,
const Eigen::Matrix3d &  orientation 
) const
inline

Definition at line 260 of file arm.hpp.

const trajectory::Trajectory* hebi::experimental::arm::Arm::trajectory ( ) const
inline

Definition at line 105 of file arm.hpp.

bool hebi::experimental::arm::Arm::update ( )

Definition at line 75 of file arm.cpp.

Member Data Documentation

Eigen::VectorXd hebi::experimental::arm::Arm::accel_
private

Definition at line 300 of file arm.hpp.

Eigen::MatrixXd hebi::experimental::arm::Arm::aux_
private

Definition at line 308 of file arm.hpp.

Eigen::VectorXd hebi::experimental::arm::Arm::aux_times_
private

Definition at line 307 of file arm.hpp.

hebi::GroupCommand hebi::experimental::arm::Arm::command_
private

Definition at line 314 of file arm.hpp.

std::shared_ptr<EndEffectorBase> hebi::experimental::arm::Arm::end_effector_
private

Definition at line 291 of file arm.hpp.

hebi::GroupFeedback hebi::experimental::arm::Arm::feedback_
private

Definition at line 313 of file arm.hpp.

std::function<double()> hebi::experimental::arm::Arm::get_current_time_s_
private

Definition at line 287 of file arm.hpp.

std::shared_ptr<Group> hebi::experimental::arm::Arm::group_
private

Definition at line 289 of file arm.hpp.

internal::KinematicsHelper hebi::experimental::arm::Arm::kinematics_helper_
private

Definition at line 311 of file arm.hpp.

double hebi::experimental::arm::Arm::last_time_
private

Definition at line 288 of file arm.hpp.

Eigen::VectorXd hebi::experimental::arm::Arm::masses_
private

Definition at line 303 of file arm.hpp.

Eigen::VectorXd hebi::experimental::arm::Arm::pos_
private

Definition at line 298 of file arm.hpp.

std::shared_ptr<robot_model::RobotModel> hebi::experimental::arm::Arm::robot_model_
private

Definition at line 290 of file arm.hpp.

std::shared_ptr<trajectory::Trajectory> hebi::experimental::arm::Arm::trajectory_
private

Definition at line 294 of file arm.hpp.

double hebi::experimental::arm::Arm::trajectory_start_time_ { std::numeric_limits<double>::quiet_NaN() }
private

Definition at line 295 of file arm.hpp.

Eigen::VectorXd hebi::experimental::arm::Arm::vel_
private

Definition at line 299 of file arm.hpp.


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


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