mirror of https://github.com/fan-ziqi/rl_sar.git
fix: multi ros version support
This commit is contained in:
parent
c4514d235c
commit
a5e54c323a
|
@ -52,14 +52,14 @@ def generate_launch_description():
|
||||||
|
|
||||||
joint_state_broadcaster_node = Node(
|
joint_state_broadcaster_node = Node(
|
||||||
package="controller_manager",
|
package="controller_manager",
|
||||||
executable="spawner",
|
executable='spawner.py' if os.environ.get('ROS_DISTRO', '') == 'foxy' else 'spawner',
|
||||||
arguments=["joint_state_broadcaster"],
|
arguments=["joint_state_broadcaster"],
|
||||||
output="screen",
|
output="screen",
|
||||||
)
|
)
|
||||||
|
|
||||||
robot_joint_controller_node = Node(
|
robot_joint_controller_node = Node(
|
||||||
package="controller_manager",
|
package="controller_manager",
|
||||||
executable="spawner",
|
executable='spawner.py' if os.environ.get('ROS_DISTRO', '') == 'foxy' else 'spawner',
|
||||||
arguments=["robot_joint_controller"],
|
arguments=["robot_joint_controller"],
|
||||||
output="screen",
|
output="screen",
|
||||||
)
|
)
|
||||||
|
|
|
@ -19,7 +19,7 @@ from ament_index_python.packages import get_package_share_directory
|
||||||
from rl_sdk import *
|
from rl_sdk import *
|
||||||
from observation_buffer import *
|
from observation_buffer import *
|
||||||
|
|
||||||
CSV_LOGGER = True
|
CSV_LOGGER = False
|
||||||
|
|
||||||
class RL_Sim(RL, Node):
|
class RL_Sim(RL, Node):
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
#include "rl_sim.hpp"
|
#include "rl_sim.hpp"
|
||||||
|
|
||||||
// #define PLOT
|
// #define PLOT
|
||||||
#define CSV_LOGGER
|
// #define CSV_LOGGER
|
||||||
|
|
||||||
RL_Sim::RL_Sim()
|
RL_Sim::RL_Sim()
|
||||||
: rclcpp::Node("rl_sim_node")
|
: rclcpp::Node("rl_sim_node")
|
||||||
|
@ -25,17 +25,23 @@ RL_Sim::RL_Sim()
|
||||||
auto future = param_client->async_send_request(request);
|
auto future = param_client->async_send_request(request);
|
||||||
auto status = rclcpp::spin_until_future_complete(this->get_node_base_interface(), future, std::chrono::seconds(5));
|
auto status = rclcpp::spin_until_future_complete(this->get_node_base_interface(), future, std::chrono::seconds(5));
|
||||||
|
|
||||||
if (status == rclcpp::FutureReturnCode::SUCCESS) {
|
if (status == rclcpp::FutureReturnCode::SUCCESS)
|
||||||
|
{
|
||||||
auto result = future.get();
|
auto result = future.get();
|
||||||
if (result->values.size() < 2) {
|
if (result->values.size() < 2)
|
||||||
|
{
|
||||||
std::cout << LOGGER::ERROR << "Failed to get all parameters from param_node" << std::endl;
|
std::cout << LOGGER::ERROR << "Failed to get all parameters from param_node" << std::endl;
|
||||||
} else {
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
this->robot_name = result->values[0].string_value;
|
this->robot_name = result->values[0].string_value;
|
||||||
this->gazebo_model_name = result->values[1].string_value;
|
this->gazebo_model_name = result->values[1].string_value;
|
||||||
std::cout << LOGGER::INFO << "Get param robot_name: " << this->robot_name << std::endl;
|
std::cout << LOGGER::INFO << "Get param robot_name: " << this->robot_name << std::endl;
|
||||||
std::cout << LOGGER::INFO << "Get param gazebo_model_name: " << this->gazebo_model_name << std::endl;
|
std::cout << LOGGER::INFO << "Get param gazebo_model_name: " << this->gazebo_model_name << std::endl;
|
||||||
}
|
}
|
||||||
} else {
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
std::cout << LOGGER::ERROR << "Failed to call param_node service" << std::endl;
|
std::cout << LOGGER::ERROR << "Failed to call param_node service" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -37,7 +37,11 @@ typedef struct
|
||||||
|
|
||||||
namespace robot_joint_controller
|
namespace robot_joint_controller
|
||||||
{
|
{
|
||||||
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
|
#if defined(ROS_DISTRO_FOXY)
|
||||||
|
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
|
||||||
|
#elif defined(ROS_DISTRO_HUMBLE)
|
||||||
|
using CallbackReturn = controller_interface::CallbackReturn;
|
||||||
|
#endif
|
||||||
|
|
||||||
class RobotJointController : public controller_interface::ControllerInterface
|
class RobotJointController : public controller_interface::ControllerInterface
|
||||||
{
|
{
|
||||||
|
@ -50,15 +54,14 @@ public:
|
||||||
controller_interface::return_type update() override;
|
controller_interface::return_type update() override;
|
||||||
#elif defined(ROS_DISTRO_HUMBLE)
|
#elif defined(ROS_DISTRO_HUMBLE)
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
controller_interface::CallbackReturn on_init() override;
|
|
||||||
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||||
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
|
CallbackReturn on_init() override;
|
||||||
#endif
|
#endif
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
||||||
// ROBOT_JOINT_CONTROLLER_PUBLIC
|
|
||||||
// CallbackReturn on_init() override;
|
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override;
|
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override;
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
|
|
|
@ -37,7 +37,11 @@ typedef struct
|
||||||
|
|
||||||
namespace robot_joint_controller
|
namespace robot_joint_controller
|
||||||
{
|
{
|
||||||
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
|
#if defined(ROS_DISTRO_FOXY)
|
||||||
|
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
|
||||||
|
#elif defined(ROS_DISTRO_HUMBLE)
|
||||||
|
using CallbackReturn = controller_interface::CallbackReturn;
|
||||||
|
#endif
|
||||||
|
|
||||||
class RobotJointControllerGroup : public controller_interface::ControllerInterface
|
class RobotJointControllerGroup : public controller_interface::ControllerInterface
|
||||||
{
|
{
|
||||||
|
@ -50,15 +54,14 @@ public:
|
||||||
controller_interface::return_type update() override;
|
controller_interface::return_type update() override;
|
||||||
#elif defined(ROS_DISTRO_HUMBLE)
|
#elif defined(ROS_DISTRO_HUMBLE)
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
controller_interface::CallbackReturn on_init() override;
|
|
||||||
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||||
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
|
CallbackReturn on_init() override;
|
||||||
#endif
|
#endif
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
||||||
// ROBOT_JOINT_CONTROLLER_PUBLIC
|
|
||||||
// CallbackReturn on_init() override;
|
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override;
|
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override;
|
||||||
ROBOT_JOINT_CONTROLLER_PUBLIC
|
ROBOT_JOINT_CONTROLLER_PUBLIC
|
||||||
|
|
|
@ -18,10 +18,12 @@ RobotJointController::RobotJointController()
|
||||||
memset(&servo_command_, 0, sizeof(ServoCommand));
|
memset(&servo_command_, 0, sizeof(ServoCommand));
|
||||||
}
|
}
|
||||||
|
|
||||||
CallbackReturn RobotJointController::on_init()
|
#if defined(ROS_DISTRO_HUMBLE)
|
||||||
|
CallbackReturn RobotJointControllerGroup::on_init()
|
||||||
{
|
{
|
||||||
return CallbackReturn::SUCCESS;
|
return CallbackReturn::SUCCESS;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
CallbackReturn RobotJointController::on_configure(const rclcpp_lifecycle::State &previous_state)
|
CallbackReturn RobotJointController::on_configure(const rclcpp_lifecycle::State &previous_state)
|
||||||
{
|
{
|
||||||
|
|
|
@ -16,10 +16,12 @@ RobotJointControllerGroup::RobotJointControllerGroup()
|
||||||
memset(&servo_command_, 0, sizeof(ServoCommand));
|
memset(&servo_command_, 0, sizeof(ServoCommand));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(ROS_DISTRO_HUMBLE)
|
||||||
CallbackReturn RobotJointControllerGroup::on_init()
|
CallbackReturn RobotJointControllerGroup::on_init()
|
||||||
{
|
{
|
||||||
return CallbackReturn::SUCCESS;
|
return CallbackReturn::SUCCESS;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
CallbackReturn RobotJointControllerGroup::on_configure(const rclcpp_lifecycle::State &previous_state)
|
CallbackReturn RobotJointControllerGroup::on_configure(const rclcpp_lifecycle::State &previous_state)
|
||||||
{
|
{
|
||||||
|
|
|
@ -38,14 +38,14 @@ def generate_launch_description():
|
||||||
|
|
||||||
joint_state_broadcaster_node = Node(
|
joint_state_broadcaster_node = Node(
|
||||||
package="controller_manager",
|
package="controller_manager",
|
||||||
executable="spawner",
|
executable='spawner.py' if os.environ.get('ROS_DISTRO', '') == 'foxy' else 'spawner',
|
||||||
arguments=["joint_state_broadcaster"],
|
arguments=["joint_state_broadcaster"],
|
||||||
output='screen',
|
output='screen',
|
||||||
)
|
)
|
||||||
|
|
||||||
robot_joint_controller_node = Node(
|
robot_joint_controller_node = Node(
|
||||||
package="controller_manager",
|
package="controller_manager",
|
||||||
executable="spawner",
|
executable='spawner.py' if os.environ.get('ROS_DISTRO', '') == 'foxy' else 'spawner',
|
||||||
arguments=["robot_joint_controller"],
|
arguments=["robot_joint_controller"],
|
||||||
output='screen',
|
output='screen',
|
||||||
)
|
)
|
||||||
|
|
|
@ -46,7 +46,7 @@ def generate_launch_description():
|
||||||
|
|
||||||
controller_nodes = [Node(
|
controller_nodes = [Node(
|
||||||
package="controller_manager",
|
package="controller_manager",
|
||||||
executable="spawner",
|
executable='spawner.py' if os.environ.get('ROS_DISTRO', '') == 'foxy' else 'spawner',
|
||||||
arguments=[name],
|
arguments=[name],
|
||||||
output='screen',
|
output='screen',
|
||||||
) for name in controller_names]
|
) for name in controller_names]
|
||||||
|
|
Loading…
Reference in New Issue