Skip to content

Commit

Permalink
Some fixed for ROS 2 jazzy:
Browse files Browse the repository at this point in the history
- API changes in ROS 2 control
- Fix for generate parameter library (seems to be a bug on their side)
  • Loading branch information
dmronga committed Dec 4, 2024
1 parent 4be8db4 commit a20f6b7
Show file tree
Hide file tree
Showing 7 changed files with 15 additions and 9 deletions.
2 changes: 1 addition & 1 deletion include/wbc_ros/cartesian_position_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class CartesianPositionController : public controller_interface::ChainableContro
cartesian_position_controller::Params params;

virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces();
virtual controller_interface::return_type update_reference_from_subscribers();
virtual controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period);

void setpoint_callback(const RbsMsgPtr msg);
void feedback_callback(const RbsMsgPtr msg);
Expand Down
2 changes: 1 addition & 1 deletion include/wbc_ros/joint_position_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class JointPositionController : public controller_interface::ChainableController
}

virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces();
virtual controller_interface::return_type update_reference_from_subscribers();
virtual controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period);
public:
JointPositionController();
~JointPositionController(){}
Expand Down
2 changes: 1 addition & 1 deletion include/wbc_ros/whole_body_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ class WholeBodyController : public controller_interface::ChainableControllerInte

protected:
virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces();
virtual controller_interface::return_type update_reference_from_subscribers();
virtual controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period);
};

}
Expand Down
2 changes: 1 addition & 1 deletion src/cartesian_position_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ vector<hardware_interface::CommandInterface> CartesianPositionController::on_exp
return interfaces;
}

controller_interface::return_type CartesianPositionController::update_reference_from_subscribers(){
controller_interface::return_type CartesianPositionController::update_reference_from_subscribers(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/){
setpoint_msg = *rt_setpoint_buffer.readFromRT();
if(!setpoint_msg.get())
return controller_interface::return_type::OK;
Expand Down
2 changes: 1 addition & 1 deletion src/joint_position_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ std::vector<hardware_interface::CommandInterface> JointPositionController::on_ex
return interfaces;
}

controller_interface::return_type JointPositionController::update_reference_from_subscribers(){
controller_interface::return_type JointPositionController::update_reference_from_subscribers(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/){
setpoint_msg = *rt_setpoint_buffer.readFromRT();
if(!setpoint_msg.get())
return controller_interface::return_type::OK;
Expand Down
2 changes: 1 addition & 1 deletion src/whole_body_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ std::vector<CommandInterface> WholeBodyController::on_export_reference_interface
return interfaces;
}

controller_interface::return_type WholeBodyController::update_reference_from_subscribers(){
controller_interface::return_type WholeBodyController::update_reference_from_subscribers(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/){
return controller_interface::return_type::OK;
}

Expand Down
12 changes: 9 additions & 3 deletions src/whole_body_controller_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,14 @@ whole_body_controller:
one_of<>: [["velocity", "acceleration"]]
}
}
robot_description: {
type: string,
default_value: "",
description: "Robot URDF.",
validation: {
not_empty<>: null
}
}
command_interfaces: {
type: string_array,
default_value: [],
Expand Down Expand Up @@ -53,9 +61,7 @@ whole_body_controller:
description: "The joint weights control the contribution of each individual joint to the solution. Values have to be within [0,1].
A zero means here that the joint is not used at all. Size has to be same as number of robot joints.",
validation: {
not_empty<>: null,
lower_element_bounds: [0.0],
upper_element_bounds: [1.0],
not_empty<>: null,
}
}
robot_model:
Expand Down

0 comments on commit a20f6b7

Please sign in to comment.