Class OmniWheels4X
Defined in File OmniWheels4X.h
Inheritance Relationships
Base Type
public OpenSoT::Constraint< Eigen::MatrixXd, Eigen::VectorXd >
(Template Class Constraint)
Class Documentation
-
class OmniWheels4X : public OpenSoT::Constraint<Eigen::MatrixXd, Eigen::VectorXd>
The OmniWheels4X class implements a constraint to map base velocities into (omni-)wheels for a 4 drive case.
The kinematic model is based on: “An admittance-controlled wheeled mobile manipulator for mobility assistance:
Human–robot interaction estimation and redundancy resolution for enhanced force exertion ability” by Hongjun Xing et al., Mechatronics, April 2021
Public Types
-
typedef std::shared_ptr<OmniWheels4X> Ptr
Public Functions
-
OmniWheels4X(const double l1, const double l2, const double r, const std::vector<std::string> joint_wheels_name, const std::string base_link, XBot::ModelInterface &robot)
OmniWheel4X maps base velocities (XY-YAW) into wheels velocities.
| x | y____| l1 ------ __ __ |fl|________|fr| |__| |__| | | | | l2 | | | | | __| |__ |hl|________|hr| |__| |__|
Note
we suppose the base_link at the center of the mobile base
Note
we assume a floating base robot
- Parameters
l1 – y distance from the base frame to the center of the wheel (see figure)
l2 – x distance from the base frame to the center of the wheel (see figure)
r – wheel radius
joint_wheels_name – ordered list of joint names representing the wheels [fl, fr, hl, hr]
base_link – of the mobile base assumed to be at the center
x – initial configuration of the robot when creating the constraint
robot – the robot model
-
virtual void update()
update the constraint
- Parameters
x – state vector
-
inline void setIsGlobalVelocity(bool is_global_velocity)
setIsGlobalVelocity set the flag to consider the velocity in the global frame
- Parameters
is_global_velocity – default is false
-
inline bool getIsGlobalVelocity() const
getIsGlobalVelocity get the flag to consider the velocity in the global frame
- Returns
true or false
-
typedef std::shared_ptr<OmniWheels4X> Ptr