![]() |
ORCA: Optimization-based framework for Robotic Control Applications
|
A Wrench sensor w.r.t. a base_link. Wrench is expressed from the world to the body, in the base_link frame. More...
#include <Utils.h>
Public Member Functions | |
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... | |
Protected Member Functions | |
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 () |
A Wrench sensor w.r.t. a base_link. Wrench is expressed from the world to the body, in the base_link frame.
This class is a wrapper to a ForceTorqueSensor or ContactSensor to store frame information. Indeed there is no easy way to get the attributes of the Gazebo sensor.
|
inline |
|
inlinevirtual |
|
inlineprotected |
|
inline |
returns the wrench in the base_link name, from the world to the body
|
inline |
returns the wrench in the base_link frame
|
inlineprotected |
|
inlineprotected |
sets the wrench in the base_link frame
|
inlineprotected |