Skip to content

Conversation

@mergify
Copy link
Contributor

@mergify mergify bot commented Oct 17, 2025

In #2571, potential crash was introduced:

read() can be called before perform_command_mode_switch(), which would result in a segfault accessing this vector.

Example stack trace in that case:

[ros2_control_node-1] Stack trace (most recent call last) in thread 186502:                                                                                   
[ros2_control_node-1] #10   Object "/usr/lib/x86_64-linux-gnu/ld-linux-x86-64.so.2", at 0xffffffffffffffff, in                                                
[ros2_control_node-1] #9    Source "../sysdeps/unix/sysv/linux/x86_64/clone.S", line 100, in clone [0x763f54868a63]                                           
[ros2_control_node-1] #8    Source "./nptl/pthread_create.c", line 447, in start_thread [0x763f547dbaa3]                                                      
[ros2_control_node-1] #7    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.33", at 0x763f54a3ddb3, in                                                     
[ros2_control_node-1] #6    Source "/home/robot/checkout/ros2_control_rolling/colcon_ws/src/ros2_control/controller_manager/src/ros2_control_node.cpp", line 146, in operator() [0x5f7cf59af521]
[ros2_control_node-1]         143:         previous_time = current_time;                                                                                      
[ros2_control_node-1]         144:                                                                                                                            
[ros2_control_node-1]         145:         // execute update loop                                                                                             
[ros2_control_node-1]       > 146:         cm->read(cm->get_trigger_clock()->now(), measured_period);                                                         
[ros2_control_node-1]         147:         cm->update(cm->get_trigger_clock()->now(), measured_period);                                                       
[ros2_control_node-1]         148:         cm->write(cm->get_trigger_clock()->now(), measured_period);                                                        
[ros2_control_node-1] #5    Source "/home/robot/checkout/ros2_control_rolling/colcon_ws/src/ros2_control/controller_manager/src/controller_manager.cpp", line 2844, in read [0x763f54f06b2c]
[ros2_control_node-1]        2841: {
[ros2_control_node-1]        2842:   periodicity_stats_.add_measurement(1.0 / period.seconds());
[ros2_control_node-1]        2843:   const auto start_time = std::chrono::steady_clock::now();
[ros2_control_node-1]       >2844:   auto [result, failed_hardware_names] = resource_manager_->read(time, period);
[ros2_control_node-1]        2845:                                                                                                                            
[ros2_control_node-1]        2846:   if (result != hardware_interface::return_type::OK)                
[ros2_control_node-1]        2847:   {                                                                                                                        
[ros2_control_node-1] #4    Source "/home/robot/checkout/ros2_control_rolling/colcon_ws/src/ros2_control/hardware_interface/src/resource_manager.cpp", line 2423, in read [0x763f546a6915]
[ros2_control_node-1]        2421:   read_components(resource_storage_->actuators_);
[ros2_control_node-1]        2422:   read_components(resource_storage_->sensors_);
[ros2_control_node-1]       >2423:   read_components(resource_storage_->systems_);              
[ros2_control_node-1]        2424:                                                                                                                            
[ros2_control_node-1]        2425:   return read_write_status;                                                                                                
[ros2_control_node-1]        2426: }
[ros2_control_node-1] #3    Source "/home/robot/checkout/ros2_control_rolling/colcon_ws/src/ros2_control/hardware_interface/src/resource_manager.cpp", line 2364, in operator()<std::vector<hardware_interface::HardwareComponent> > [0x763f546a6005]
[ros2_control_node-1]        2361:           hardware_component_info.rw_rate == 0 ||
[ros2_control_node-1]        2362:           hardware_component_info.rw_rate == resource_storage_->cm_update_rate_)                                           
[ros2_control_node-1]        2363:         {
[ros2_control_node-1]       >2364:           ret_val = component.read(current_time, period);
[ros2_control_node-1]        2365:         }                                                                                                                  
[ros2_control_node-1]        2366:         else                                                                                                               
[ros2_control_node-1]        2367:         {
[ros2_control_node-1] #2    Source "/home/robot/checkout/ros2_control_rolling/colcon_ws/src/ros2_control/hardware_interface/src/hardware_component.cpp", line 373, in read [0x763f546f51ea]
[ros2_control_node-1]         370:     impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
[ros2_control_node-1]         371:     impl_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)                                 
[ros2_control_node-1]         372:   {                                                                                                                        
[ros2_control_node-1]       > 373:     const auto trigger_result = impl_->trigger_read(time, period);
[ros2_control_node-1]         374:     if (trigger_result.result == return_type::ERROR)                            
[ros2_control_node-1]         375:     {    
[ros2_control_node-1]         376:       error();                                                                                                             
[ros2_control_node-1] #1    Source "/home/robot/checkout/ros2_control_rolling/colcon_ws/src/ros2_control/hardware_interface/include/hardware_interface/hardware_component_interface.hpp", line 639, in trigger_read [0x763f5470a8fa]
[ros2_control_node-1]         636:     {       
[ros2_control_node-1]         637:       const auto start_time = std::chrono::steady_clock::now();
[ros2_control_node-1]         638:       status.successful = true;                                                                                            
[ros2_control_node-1]       > 639:       status.result = read(time, period);
[ros2_control_node-1]         640:       status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(           
[ros2_control_node-1]         641:         std::chrono::steady_clock::now() - start_time);                                   
[ros2_control_node-1]         642:     }
[ros2_control_node-1] #0    Source "/home/robot/checkout/ros2_control_rolling/colcon_ws/src/ros2_control/hardware_interface/src/mock_components/generic_system.cpp", line 424, in read [0x763f442ac2f5]
[ros2_control_node-1]         421:         }                                                                                                                  
[ros2_control_node-1]         422:       }
[ros2_control_node-1]         423:                                             
[ros2_control_node-1]       > 424:       switch (joint_control_mode_[j])                                                                                      
[ros2_control_node-1]         425:       {                            
[ros2_control_node-1]         426:         case ACCELERATION_INTERFACE_INDEX:
[ros2_control_node-1]         427:         {                                                                                                                  
[ros2_control_node-1] Segmentation fault (Address not mapped to object [(nil)]) 

By moving initialization of the joint_control_mode_ vector to on_configure() we can make sure to have it initialized with the correct amount of joints.


This is an automatic backport of pull request #2693 done by [Mergify](https://mergify.com).

@mergify mergify bot added the conflicts label Oct 17, 2025
@mergify
Copy link
Contributor Author

mergify bot commented Oct 17, 2025

Cherry-pick of c99442e has failed:

On branch mergify/bp/jazzy/pr-2693
Your branch is up to date with 'origin/jazzy'.

You are currently cherry-picking commit c99442e.
  (fix conflicts and run "git cherry-pick --continue")
  (use "git cherry-pick --skip" to skip this patch)
  (use "git cherry-pick --abort" to cancel the cherry-pick operation)

Unmerged paths:
  (use "git add <file>..." to mark resolution)
	both modified:   hardware_interface/include/mock_components/generic_system.hpp
	both modified:   hardware_interface/src/mock_components/generic_system.cpp

no changes added to commit (use "git add" and/or "git commit -a")

To fix up this pull request, you can check it out locally. See documentation: https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/reviewing-changes-in-pull-requests/checking-out-pull-requests-locally

@mergify
Copy link
Contributor Author

mergify bot commented Oct 19, 2025

This pull request is in conflict. Could you fix it @bmagyar @destogl @christophfroehlich @saikishor?

@christophfroehlich christophfroehlich merged commit 121636a into jazzy Oct 19, 2025
14 checks passed
@christophfroehlich christophfroehlich deleted the mergify/bp/jazzy/pr-2693 branch October 19, 2025 16:22
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants