From 3d2c30b74afb5f3dc6c1612bcce696b83cb50dd7 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Thu, 26 Sep 2024 15:01:06 +0200 Subject: [PATCH] Fix header --- .../include/bitbots_quintic_walk/walk_node.hpp | 2 +- .../include/bitbots_quintic_walk/walk_pywrapper.hpp | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp index 7ab784873..ad2da928c 100644 --- a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp +++ b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp @@ -54,7 +54,7 @@ namespace bitbots_quintic_walk { class WalkNode { public: explicit WalkNode(rclcpp::Node::SharedPtr node, const std::string &ns = "", - std::vector moveit_parameters = {}); + const std::vector &moveit_parameters = {}); bitbots_msgs::msg::JointCommand step(double dt); bitbots_msgs::msg::JointCommand step(double dt, geometry_msgs::msg::Twist::SharedPtr cmdvel_msg, sensor_msgs::msg::Imu::SharedPtr imu_msg, diff --git a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp index dfe8f47c2..258689f77 100644 --- a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp +++ b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp @@ -23,8 +23,9 @@ using namespace ros2_python_extension; class PyWalkWrapper { public: - explicit PyWalkWrapper(std::string ns, std::vector walk_parameter_msgs = {}, - std::vector moveit_parameter_msgs = {}, bool force_smooth_step_transition = false); + explicit PyWalkWrapper(const std::string &ns, const std::vector &walk_parameter_msgs = {}, + const std::vector &moveit_parameter_msgs = {}, + bool force_smooth_step_transition = false); py::bytes step(double dt, py::bytes &cmdvel_msg, py::bytes &imu_msg, py::bytes &jointstate_msg, py::bytes &pressure_left, py::bytes &pressure_right); py::bytes step_relative(double dt, py::bytes &step_msg, py::bytes &imu_msg, py::bytes &jointstate_msg,