Migration from ROS 2 Humble to ROS 2 Jazzy
This document summarizes the key changes when migrating from ROS 2 Humble to ROS 2 Jazzy. For detailed, code-level guidance, refer to the relevant official migration guides in the ROS 2 documentation.
Bringup
MoveItConfigsBuilder Updates
Use
.planning_pipelines()to explicitly specifyplanning_plugins,default_planning_pipeline, andload_all.default_planning_pipelineis now mandatory — omitting it may result in runtime errors.After
.to_moveit_configs(), call.to_dict()to properly pass configuration to bothMoveGroupandRViznodes.
Dynamic YAML Configuration
Introduce a new launch argument
dynamic_yamlto generate controller configuration YAML dynamically at runtime.The system parses the
robot_descriptionto extract active/passive joint data and constructs controller YAML automatically.If a specific controller YAML (e.g.
dsr_controller2_<model>.yaml) is not found, it falls back todsr_controller2.yaml.
Launch Flow Refactoring
Sequential node startup using
OnProcessExitreplaces previous parallel launch patterns.Recommended launch sequence:
set_config_node → ros2_control_node → joint_state_broadcaster → dsr_controller2 → dsr_moveit_controller → move_group + RViz2
set_config_nodesets hardware parameters then triggersros2_control_node.joint_state_broadcasternow runs early to ensure/joint_statesis available from the start.
Hardware Interface (dsr_hw_interface2)
New Hardware-Centric Architecture
Migration from
ControllerInterfacetoSystemInterfaceunder Jazzy.Initialization steps (DRFL init, callback registration, parameter parsing) now reside in the hardware layer.
Full support for lifecycle hooks:
on_init(),on_configure(),on_activate().
Callback Refactor
All monitoring callbacks (
OnMonitoringState,OnMonitoringDataEx,OnDisconnected,OnLogAlarm) are now managed in the hardware layer.These callbacks are registered in
DRHWInterface::on_init()oron_activate()for consistency.
Flexible DOF Handling & Parameters
Robot metadata (model name, degrees of freedom, gripper type) are parsed from
HardwareInfo.Arrays such as
joint_position_,joint_velocity_, andcommand_are resized dynamically based on joint count.
Hardware Mapping
hw_mapping_enables mapping between URDF/SRDF joint names and internal DRFL indices.Facilitates clarity and support for multiple robot configurations.
Real-Time Control Enhancements
Use
rt_hostinstead ofhostin DRCF versions ≥ 3.0.Functions like
set_rt_control_output()andstart_rt_control()execute only in robot mode (not emulator).
Monitoring Upgrades
Replaced
OnMonitoringDataCBwithOnMonitoringDataExCBandOnMonitoringCtrlIOExCB.Offers access to force/torque/position data in tool, world, and user frames — ideal for advanced compliance controls.
Additional Improvements
Real-time error monitoring added via
/errortopic usingLogAlarmcallback.Emulator detection: automatic via loopback IP (
127.0.0.1).
Xacro Fixes
Define
piexpressions withxacro:propertyat the top:<xacro:property name="double_pi" value="${2.0 * pi}"/> <xacro:property name="neg_double_pi" value="${-2.0 * pi}"/> <xacro:property name="neg_pi" value="${-1.0 * pi}"/>
Jazzy’s
ros2_controlcannot parse raw{2*pi}expressions.Always use
${...}syntax and define viaxacro:property.
SRDF Fixes
Ensure
<robot name="...">matches the URDFname:<!-- Before --> <robot name="dsr"> <!-- After --> <robot name="m1013">
Jazzy requires exact match between URDF and SRDF robot names.
A mismatch will trigger an error:
Semantic description is not specified for the same robot as the URDF
_planning.yaml Fixes (MoveIt2)
Replace
planning_plugin(string) withplanning_plugins(array of strings).Separate adapters into
request_adaptersandresponse_adapters:planning_plugins: - ompl_interface/OMPLPlanner request_adapters: - default_planning_request_adapters/ResolveConstraintFrames - default_planning_request_adapters/ValidateWorkspaceBounds - default_planning_request_adapters/CheckStartStateBounds - default_planning_request_adapters/CheckStartStateCollision response_adapters: - default_planning_response_adapters/AddTimeOptimalParameterization - default_planning_response_adapters/ValidateSolution - default_planning_response_adapters/DisplayMotionPath
Lists must use a hyphen-prefixed format (
- item) asstring_array.
QoS Changes
Deprecated:
rmw_qos_profile_*Use
rclcpp::QoSfor all publishers and subscribers in C++:auto qos = rclcpp::QoS(10).best_effort(); node->create_subscription<MsgType>("topic", qos, callback);
Default QoS policy updates: -
reliable→best_effort-transient_local→volatile
Summary of Official ros2_control Migration Highlights
According to the official ROS 2 Jazzy migration guides and release notes:
diff_drive_controller
- cmd_vel must now use a stamped twist message.
- Deprecated parameters: has_velocity_limits, has_acceleration_limits, has_jerk_limits — set limits to .NAN instead.
gripper_action_controller
- Legacy controllers (effort_..., position_...) removed. Use parallel_gripper_action_controller/GripperActionController.
joint_trajectory_controller
- Default allow_nonzero_velocity_at_trajectory_end is now false.
- start_with_holding removed; always holds on activation.
- Cancels goals on on_deactivate.
- Discards empty trajectories.
- Angle wraparound auto-detected from URDF continuous joints; remove angle_wraparound parameter.