Skip to content

Commit

Permalink
Increase the URDF velocity limits of the diffbot_urdf for the chainin…
Browse files Browse the repository at this point in the history
…g test
  • Loading branch information
saikishor committed Jan 8, 2025
1 parent c4d023c commit c78338f
Showing 1 changed file with 6 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <gtest/gtest.h>
#include <memory>
#include <regex>
#include <string>
#include <unordered_map>
#include <utility>
Expand Down Expand Up @@ -103,18 +104,16 @@ class TestControllerChainingWithControllerManager
public testing::WithParamInterface<Strictness>
{
public:
TestControllerChainingWithControllerManager()
: ControllerManagerFixture<TestableControllerManager>(
ros2_control_test_assets::minimal_robot_urdf_no_limits)
{
}

void SetUp()
{
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
const std::regex velocity_pattern(R"(velocity\s*=\s*"-?[0-9]+(\.[0-9]+)?")");
const std::string velocity_replacement = R"(velocity="10000.0")";
const std::string diffbot_urdf_large_limits = std::regex_replace(
ros2_control_test_assets::diffbot_urdf, velocity_pattern, velocity_replacement);
cm_ = std::make_shared<TestableControllerManager>(
std::make_unique<hardware_interface::ResourceManager>(
ros2_control_test_assets::diffbot_urdf, rm_node_->get_node_clock_interface(),
diffbot_urdf_large_limits, rm_node_->get_node_clock_interface(),
rm_node_->get_node_logging_interface(), true),
executor_, TEST_CM_NAME);
run_updater_ = false;
Expand Down

0 comments on commit c78338f

Please sign in to comment.