-
Notifications
You must be signed in to change notification settings - Fork 786
[Reference Only/Draft] gazebo_ros_control ROS2 port #1083
Conversation
Signed-off-by: Louise Poubel <[email protected]>
All other sensor publishers were updated previously to use the same profile (#926). I'm not sure if the image publishers were overlooked or the image_transport API didn't support setting the QoS profile at the time. Signed-off-by: Jacob Perron <[email protected]>
* [ros2] make transient local reliable (#1033) * make transient local reliable Signed-off-by: Karsten Knese <[email protected]> * fix master Signed-off-by: Karsten Knese <[email protected]> * add launch test Signed-off-by: Karsten Knese <[email protected]> * make it actual latched Signed-off-by: Karsten Knese <[email protected]> * alpha sort Signed-off-by: Karsten Knese <[email protected]> * add launch_test dependency Signed-off-by: Karsten Knese <[email protected]> * more dependencies Signed-off-by: Karsten Knese <[email protected]> * remove debug print Signed-off-by: Karsten Knese <[email protected]> * is_initialized -> ok Signed-off-by: Karsten Knese <[email protected]> * Update gazebo_ros/test/entity_spawner.test.py Co-Authored-By: chapulina <[email protected]> * use erase-remove idiom Signed-off-by: Karsten Knese <[email protected]> * use ReadyToTest() Signed-off-by: Karsten Knese <[email protected]> Co-authored-by: chapulina <[email protected]> * Set timeout and call gzserver directly Signed-off-by: Louise Poubel <[email protected]> Co-authored-by: chapulina <[email protected]>
| hardware_interface::JointStateInterface js_interface_; | ||
| hardware_interface::EffortJointInterface ej_interface_; | ||
| hardware_interface::PositionJointInterface pj_interface_; | ||
| hardware_interface::VelocityJointInterface vj_interface_; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
my coffeebot simulation uses a function in EffortJointInterface to translate trajectories from joint_trajectory_controller to effort values. Hence the rest is disabled.
| joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_; | ||
| joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_; | ||
| joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_; | ||
| joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Similar to the above, I only use a function from EffortJointSaturationInterface to clamp my effort values.
| std::vector<double> joint_vel_limits_; | ||
| std::vector<ControlMethod> joint_control_methods_; | ||
| #if 0 | ||
| std::vector<control_toolbox::Pid> pid_controllers_; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I havent found use for control_toolbox::Pid in gazebo_ros_controls, hence I disabled it. However, in another joint_trajectory_controller draft I used control_toolbox::Pid as part the code for converting trajectories to effort values. I'll link the joint_trajectory_controller PR later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
| // Controller manager | ||
| std::shared_ptr<controller_manager::ControllerManager> controller_manager_; | ||
| std::shared_ptr<controller_interface::ControllerInterface> controller_; | ||
| std::shared_ptr<controller_interface::ControllerInterface> controller2_; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
These 2 controllers are custom code. Normally you'd get the controller_manager to spawn controllers but this functionality is not available as of this writing. Might be wise to wait for that functionality before porting.
| /// \brief Gazebo plugin version of RobotHW | ||
| /// | ||
| /// An object of class RobotHWSim represents a robot's simulated hardware. | ||
| class RobotHWSim : public hardware_interface::RobotHardware |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
RobotHWSim used to inherit from hardware_interface::RobotHW, but in ros2 it has changed to hardware_interface::RobotHardware (and has different functionality to account for)
|
|
||
| //@note: Avoid using these functions! ros2_control was not built with gazebo_ros_control | ||
| //in mind, keep to using readSim and writeSim so we don't have to update the documents for now | ||
| virtual hardware_interface::hardware_interface_ret_t init() { } |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
as per comment, also check above.
| #else | ||
| for (auto eff_limit_handle : joint_eff_limit_handles_) | ||
| { | ||
| eff_limit_handle.enforceLimits(period); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
limits handles applied here.
|
|
||
| //@note (ddeng): these joint limits arent input into the node, so fetch them from the urdf | ||
| limits.min_position = urdf_joint->limits->lower; | ||
| limits.max_position = urdf_joint->limits->upper; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This function DefaultRobotHWSim::registerJointLimits needs some trimming; it has a bunch of repeat logic.
|
|
||
| load_params_from_yaml(controller_->get_lifecycle_node(), param_file, "coffeebot_arm_effort_controller"); | ||
| if (controller2_) | ||
| load_params_from_yaml(controller2_->get_lifecycle_node(), param_file, "coffeebot_gripper_effort_controller"); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Custom code: I load 2 controllers and associated parameter files here. Again, this functionality should be replaced by controller_manager spawn controller functionality when it has been implemented.
|
|
||
| controller_->get_lifecycle_node()->set_parameter(rclcpp::Parameter("period", sim_period.seconds())); | ||
| if (controller2_) | ||
| controller2_->get_lifecycle_node()->set_parameter(rclcpp::Parameter("period", sim_period.seconds())); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
In ROS1, iirc each controller derives off Gazebo::Node, which supplies the "period" parameter automatically. In ROS2, each controller derives off LifecycleNode and the functionality interface with Gazebo::Node hasn't been done yet. Porters should take this into account.
| joint_eff_cmdhandle_[j] = hardware_interface::JointCommandHandle( | ||
| joint_names_[j], &joint_effort_command_[j]); | ||
| //should be register_joint_effort_command_handle, but there's only 1 buffer for now | ||
| if (register_joint_command_handle(&joint_eff_cmdhandle_[j]) != hardware_interface::HW_RET_OK) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The joint commands are registered here. The controllers (joint_trajectory_controller in this case) then use the registered commands. Porters should account for how these values are fed into the controllers.
|
Closing this in favor of https://github.com/ros-simulation/gazebo_ros2_control |
The code changes in this PR was intended to work with a 'coffeebot' simulation in gazebo. It has lots of hacks, and is only meant to be an incomplete guide to porting to ROS2. Used in conjunction with ros-controls/ros2_controllers#36
Consider commits after the 18th Feb 2020, or e474da1.
Things of note will be put in reviews.
TLDR notes for porters:
Update: Also used with moveit2 training moveit/moveit2#187