Skip to content

Commit

Permalink
Merge branch 'master' into add-fake-profile-velocity
Browse files Browse the repository at this point in the history
  • Loading branch information
hellantos authored Nov 22, 2023
2 parents b196123 + 70fb66f commit 5567517
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 4 deletions.
4 changes: 2 additions & 2 deletions canopen/sphinx/quickstart/examples.rst
Original file line number Diff line number Diff line change
Expand Up @@ -9,15 +9,15 @@ Service Interface

.. code-block:: bash
ros2 launch canopen_tests ci402_setup.launch.py
ros2 launch canopen_tests cia402_setup.launch.py
Managed Service Interface
-------------------------

.. code-block:: bash
ros2 launch canopen_tests ci402_lifecycle_setup.launch.py
ros2 launch canopen_tests cia402_lifecycle_setup.launch.py
ROS2 Control
------------
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -364,7 +364,7 @@ class CIA402MockSlave : public canopen::BasicSlave
}
RCLCPP_INFO(rclcpp::get_logger("cia402_slave"), "Leaving run_profile_velocity_mode");
}

void run_homing_mode()
{
bool homed = false;
Expand Down Expand Up @@ -648,12 +648,13 @@ class CIA402MockSlave : public canopen::BasicSlave
homing_mode = std::thread(std::bind(&CIA402MockSlave::run_homing_mode, this));
}


void start_profile_velocity_mode()
{
profiled_velocity_mode =
std::thread(std::bind(&CIA402MockSlave::run_profile_velocity_mode, this));
}

void on_quickstop_active()
{
if (is_enable_operation())
Expand Down

0 comments on commit 5567517

Please sign in to comment.