Skip to content

Commit

Permalink
Revert "[ros2_control_node] Handle simulation environment clocks (ros…
Browse files Browse the repository at this point in the history
…-controls#1810)"

This reverts commit d714e8b.
  • Loading branch information
saikishor committed Nov 7, 2024
1 parent 26b7f3b commit e50e02f
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 13 deletions.
14 changes: 2 additions & 12 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,9 +57,6 @@ int main(int argc, char ** argv)
auto cm = std::make_shared<controller_manager::ControllerManager>(
executor, manager_node_name, "", cm_node_options);

const bool use_sim_time = cm->get_parameter_or("use_sim_time", false);
rclcpp::Rate rate(cm->get_update_rate(), cm->get_clock());

const bool lock_memory = cm->get_parameter_or<bool>("lock_memory", true);
std::string message;
if (lock_memory && !realtime_tools::lock_memory(message))
Expand All @@ -85,7 +82,7 @@ int main(int argc, char ** argv)
thread_priority);

std::thread cm_thread(
[cm, thread_priority, use_sim_time, &rate]()
[cm, thread_priority]()
{
if (!realtime_tools::configure_sched_fifo(thread_priority))
{
Expand Down Expand Up @@ -126,14 +123,7 @@ int main(int argc, char ** argv)

// wait until we hit the end of the period
next_iteration_time += period;
if (use_sim_time)
{
rate.sleep();
}
else
{
std::this_thread::sleep_until(next_iteration_time);
}
std::this_thread::sleep_until(next_iteration_time);
}

cm->shutdown_async_controllers_and_components();
Expand Down
1 change: 0 additions & 1 deletion doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,6 @@ controller_manager
* The ``--controller-type`` or ``-t`` spawner arg is removed. Now the controller type is defined in the controller configuration file with ``type`` field (`#1639 <https://github.com/ros-controls/ros2_control/pull/1639>`_).
* The ``--namespace`` or ``-n`` spawner arg is deprecated. Now the spawner namespace can be defined using the ROS 2 standard way (`#1640 <https://github.com/ros-controls/ros2_control/pull/1640>`_).
* Added support for the wildcard entries for the controller configuration files (`#1724 <https://github.com/ros-controls/ros2_control/pull/1724>`_).
* ``ros2_control_node`` can now handle the sim time used by different simulators, when ``use_sim_time`` is set to true (`#1810 <https://github.com/ros-controls/ros2_control/pull/1810>`_).
* The ``ros2_control_node`` node now accepts the ``thread_priority`` parameter to set the scheduler priority of the controller_manager's RT thread (`#1820 <https://github.com/ros-controls/ros2_control/pull/1820>`_).
* The ``ros2_control_node`` node has a new ``lock_memory`` parameter to lock memory at startup to physical RAM in order to avoid page faults (`#1822 <https://github.com/ros-controls/ros2_control/pull/1822>`_).
* The ``ros2_control_node`` node has a new ``cpu_affinity`` parameter to bind the process to a specific CPU core. By default, this is not enabled. (`#1852 <https://github.com/ros-controls/ros2_control/pull/1852>`_).
Expand Down

0 comments on commit e50e02f

Please sign in to comment.