remove "CONTROLLER_INTERFACE_PUBLIC"
This commit is contained in:
parent
7ed46994e4
commit
e3f518eb12
|
@ -55,7 +55,7 @@ Please use **C++ Simulation** in this [Mujoco Simulation](https://github.com/leg
|
||||||
cd ~/ros2_ws
|
cd ~/ros2_ws
|
||||||
colcon build --packages-up-to hardware_unitree_mujoco
|
colcon build --packages-up-to hardware_unitree_mujoco
|
||||||
```
|
```
|
||||||
* Launch the unitree mujoco go2 simulation
|
* Follow the guide in [unitree_mujoco](https://github.com/legubiao/unitree_mujoco) to launch the unitree mujoco go2 simulation
|
||||||
* Launch the ros2-control
|
* Launch the ros2-control
|
||||||
```bash
|
```bash
|
||||||
source ~/ros2_ws/install/setup.bash
|
source ~/ros2_ws/install/setup.bash
|
||||||
|
|
|
@ -38,6 +38,7 @@ Required hardware interfaces:
|
||||||
## 2. Build
|
## 2. Build
|
||||||
|
|
||||||
### 2.1 Build Dependencies
|
### 2.1 Build Dependencies
|
||||||
|
Before install OCS2 ROS2, please follow the guide to install [Pinocchio](https://stack-of-tasks.github.io/pinocchio/download.html), don't use the pinocchio install by rosdep!
|
||||||
|
|
||||||
* OCS2 ROS2 Libraries
|
* OCS2 ROS2 Libraries
|
||||||
```bash
|
```bash
|
||||||
|
|
|
@ -15,6 +15,7 @@
|
||||||
<depend>control_input_msgs</depend>
|
<depend>control_input_msgs</depend>
|
||||||
<depend>qpoases_colcon</depend>
|
<depend>qpoases_colcon</depend>
|
||||||
<depend>ocs2_self_collision</depend>
|
<depend>ocs2_self_collision</depend>
|
||||||
|
<depend>ocs2_legged_robot_ros</depend>
|
||||||
<depend>angles</depend>
|
<depend>angles</depend>
|
||||||
|
|
||||||
<test_depend>ament_lint_auto</test_depend>
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
|
|
@ -19,43 +19,34 @@
|
||||||
namespace ocs2::legged_robot {
|
namespace ocs2::legged_robot {
|
||||||
class Ocs2QuadrupedController final : public controller_interface::ControllerInterface {
|
class Ocs2QuadrupedController final : public controller_interface::ControllerInterface {
|
||||||
public:
|
public:
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
Ocs2QuadrupedController() = default;
|
Ocs2QuadrupedController() = default;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::return_type update(
|
controller_interface::return_type update(
|
||||||
const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_init() override;
|
controller_interface::CallbackReturn on_init() override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_configure(
|
controller_interface::CallbackReturn on_configure(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_activate(
|
controller_interface::CallbackReturn on_activate(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_deactivate(
|
controller_interface::CallbackReturn on_deactivate(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_cleanup(
|
controller_interface::CallbackReturn on_cleanup(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_shutdown(
|
controller_interface::CallbackReturn on_shutdown(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_error(
|
controller_interface::CallbackReturn on_error(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
|
|
|
@ -24,43 +24,32 @@ namespace rl_quadruped_controller {
|
||||||
|
|
||||||
class LeggedGymController final : public controller_interface::ControllerInterface {
|
class LeggedGymController final : public controller_interface::ControllerInterface {
|
||||||
public:
|
public:
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
LeggedGymController() = default;
|
LeggedGymController() = default;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::return_type update(
|
controller_interface::return_type update(
|
||||||
const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_init() override;
|
controller_interface::CallbackReturn on_init() override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_configure(
|
controller_interface::CallbackReturn on_configure(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_activate(
|
controller_interface::CallbackReturn on_activate(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_deactivate(
|
controller_interface::CallbackReturn on_deactivate(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_cleanup(
|
controller_interface::CallbackReturn on_cleanup(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_shutdown(
|
controller_interface::CallbackReturn on_shutdown(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_error(
|
controller_interface::CallbackReturn on_error(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
|
|
|
@ -33,43 +33,32 @@ namespace unitree_guide_controller {
|
||||||
|
|
||||||
class UnitreeGuideController final : public controller_interface::ControllerInterface {
|
class UnitreeGuideController final : public controller_interface::ControllerInterface {
|
||||||
public:
|
public:
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
UnitreeGuideController() = default;
|
UnitreeGuideController() = default;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::return_type update(
|
controller_interface::return_type update(
|
||||||
const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_init() override;
|
controller_interface::CallbackReturn on_init() override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_configure(
|
controller_interface::CallbackReturn on_configure(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_activate(
|
controller_interface::CallbackReturn on_activate(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_deactivate(
|
controller_interface::CallbackReturn on_deactivate(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_cleanup(
|
controller_interface::CallbackReturn on_cleanup(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_error(
|
controller_interface::CallbackReturn on_error(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
CONTROLLER_INTERFACE_PUBLIC
|
|
||||||
controller_interface::CallbackReturn on_shutdown(
|
controller_interface::CallbackReturn on_shutdown(
|
||||||
const rclcpp_lifecycle::State &previous_state) override;
|
const rclcpp_lifecycle::State &previous_state) override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue