ORCA: Optimization-based framework for Robotic Control Applications
Public Member Functions | List of all members
orca::gazebo::GazeboForceTorqueSensor Class Reference

#include <Utils.h>

+ Inheritance diagram for orca::gazebo::GazeboForceTorqueSensor:
+ Collaboration diagram for orca::gazebo::GazeboForceTorqueSensor:

Public Member Functions

 GazeboForceTorqueSensor (const std::string &base_link)
 
 GazeboForceTorqueSensor (::gazebo::physics::LinkPtr link)
 
void connectUpdate (std::function< void(::gazebo::msgs::WrenchStamped)> subscriber)
 
void setSensor (::gazebo::sensors::ForceTorqueSensorPtr sensor)
 sets the ForceTorqueSensorPtr to connect to More...
 
::gazebo::sensors::ForceTorqueSensorPtr getSensor () const
 
void setWrenchFrom (const ::gazebo::msgs::WrenchStamped &wrench_stamped)
 
- Public Member Functions inherited from orca::gazebo::GazeboWrenchSensor
 GazeboWrenchSensor ()
 
virtual ~GazeboWrenchSensor ()
 
const Eigen::Matrix< double, 6, 1 > & getWrench () const
 returns the wrench in the base_link frame More...
 
const std::string & getBaseLinkName ()
 returns the wrench in the base_link name, from the world to the body More...
 

Additional Inherited Members

- Protected Member Functions inherited from orca::gazebo::GazeboWrenchSensor
 GazeboWrenchSensor (const std::string &base_link)
 
void setConnection (::gazebo::event::ConnectionPtr conn_ptr)
 
void setWrench (const Eigen::Matrix< double, 6, 1 > &wrench)
 sets the wrench in the base_link frame More...
 
Eigen::Matrix< double, 6, 1 > & wrench ()
 

Constructor & Destructor Documentation

◆ GazeboForceTorqueSensor() [1/2]

orca::gazebo::GazeboForceTorqueSensor::GazeboForceTorqueSensor ( const std::string &  base_link)
inline

◆ GazeboForceTorqueSensor() [2/2]

orca::gazebo::GazeboForceTorqueSensor::GazeboForceTorqueSensor ( ::gazebo::physics::LinkPtr  link)
inline

Member Function Documentation

◆ connectUpdate()

void orca::gazebo::GazeboForceTorqueSensor::connectUpdate ( std::function< void(::gazebo::msgs::WrenchStamped)>  subscriber)
inline

◆ getSensor()

::gazebo::sensors::ForceTorqueSensorPtr orca::gazebo::GazeboForceTorqueSensor::getSensor ( ) const
inline

◆ setSensor()

void orca::gazebo::GazeboForceTorqueSensor::setSensor ( ::gazebo::sensors::ForceTorqueSensorPtr  sensor)
inline

sets the ForceTorqueSensorPtr to connect to

Warning
the ForceTorqueSensorPtr should be with attributes <measure_direction>child_to_parent</measure_direction> <frame>child</frame>

◆ setWrenchFrom()

void orca::gazebo::GazeboForceTorqueSensor::setWrenchFrom ( const ::gazebo::msgs::WrenchStamped &  wrench_stamped)
inline

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