include
rm_chassis_controllers
omni.h
Go to the documentation of this file.
1
//
2
// Created by qiayuan on 2022/7/29.
3
//
4
5
#pragma once
6
7
#include <Eigen/Dense>
8
9
#include "
rm_chassis_controllers/chassis_base.h
"
10
11
namespace
rm_chassis_controllers
12
{
13
class
OmniController
:
public
ChassisBase
<rm_control::RobotStateInterface, hardware_interface::EffortJointInterface>
14
{
15
public
:
16
OmniController
() =
default
;
17
bool
init
(
hardware_interface::RobotHW
* robot_hw,
ros::NodeHandle
& root_nh,
ros::NodeHandle
& controller_nh)
override
;
18
19
private
:
20
void
moveJoint
(
const
ros::Time
& time,
const
ros::Duration
& period)
override
;
21
geometry_msgs::Twist
odometry
()
override
;
22
23
std::vector<std::shared_ptr<effort_controllers::JointVelocityController>>
joints_
;
24
Eigen::MatrixXd
chassis2joints_
;
25
};
26
27
}
// namespace rm_chassis_controllers
rm_chassis_controllers::ChassisBase
Definition:
chassis_base.h:92
chassis_base.h
rm_chassis_controllers::OmniController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Definition:
omni.cpp:15
rm_chassis_controllers::OmniController::OmniController
OmniController()=default
rm_chassis_controllers::OmniController::joints_
std::vector< std::shared_ptr< effort_controllers::JointVelocityController > > joints_
Definition:
omni.h:23
rm_chassis_controllers::OmniController
Definition:
omni.h:13
hardware_interface::RobotHW
ros::Time
rm_chassis_controllers::OmniController::chassis2joints_
Eigen::MatrixXd chassis2joints_
Definition:
omni.h:24
ros::Duration
rm_chassis_controllers::OmniController::moveJoint
void moveJoint(const ros::Time &time, const ros::Duration &period) override
Definition:
omni.cpp:54
ros::NodeHandle
rm_chassis_controllers
Definition:
balance.h:15
rm_chassis_controllers::OmniController::odometry
geometry_msgs::Twist odometry() override
Definition:
omni.cpp:66
rm_chassis_controllers
Author(s): Qiayuan Liao
autogenerated on Sun May 4 2025 02:57:17