mirror of https://github.com/fan-ziqi/rl_sar.git
FIX: fix building for ROS2 Humble on Ubuntu 22.04
This commit is contained in:
parent
64fc72d613
commit
e1e3bb5de8
|
@ -18,7 +18,7 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")
|
|||
find_package(gazebo REQUIRED)
|
||||
|
||||
find_package(ament_cmake REQUIRED)
|
||||
find_package(joint_state_controller REQUIRED)
|
||||
find_package(joint_state_broadcaster REQUIRED)
|
||||
find_package(robot_state_publisher REQUIRED)
|
||||
find_package(rclcpp REQUIRED)
|
||||
find_package(gazebo_ros REQUIRED)
|
||||
|
@ -100,7 +100,7 @@ target_link_libraries(rl_real_go2
|
|||
)
|
||||
|
||||
ament_target_dependencies(rl_sim
|
||||
joint_state_controller
|
||||
joint_state_broadcaster
|
||||
robot_state_publisher
|
||||
rclcpp
|
||||
gazebo_ros
|
||||
|
|
|
@ -50,6 +50,7 @@ public:
|
|||
controller_interface::return_type update() override;
|
||||
#elif defined(ROS_DISTRO_HUMBLE)
|
||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||
controller_interface::CallbackReturn on_init() override;
|
||||
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||
#endif
|
||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||
|
|
|
@ -50,6 +50,7 @@ public:
|
|||
controller_interface::return_type update() override;
|
||||
#elif defined(ROS_DISTRO_HUMBLE)
|
||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||
controller_interface::CallbackReturn on_init() override;
|
||||
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||
#endif
|
||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||
|
|
|
@ -18,10 +18,10 @@ RobotJointController::RobotJointController()
|
|||
memset(&servo_command_, 0, sizeof(ServoCommand));
|
||||
}
|
||||
|
||||
// CallbackReturn RobotJointController::on_init()
|
||||
// {
|
||||
// return CallbackReturn::SUCCESS;
|
||||
// }
|
||||
CallbackReturn RobotJointController::on_init()
|
||||
{
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
CallbackReturn RobotJointController::on_configure(const rclcpp_lifecycle::State &previous_state)
|
||||
{
|
||||
|
|
|
@ -16,10 +16,10 @@ RobotJointControllerGroup::RobotJointControllerGroup()
|
|||
memset(&servo_command_, 0, sizeof(ServoCommand));
|
||||
}
|
||||
|
||||
// CallbackReturn RobotJointControllerGroup::on_init()
|
||||
// {
|
||||
// return CallbackReturn::SUCCESS;
|
||||
// }
|
||||
CallbackReturn RobotJointControllerGroup::on_init()
|
||||
{
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
CallbackReturn RobotJointControllerGroup::on_configure(const rclcpp_lifecycle::State &previous_state)
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue