Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Correctly load smoothing plugins in Servo integration tests #2965

Merged
merged 2 commits into from
Aug 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,9 @@ def generate_test_description():
.to_dict()
}

# This filter parameter should be >1. Increase it for greater smoothing but slower motion.
low_pass_filter_coeff = {"butterworth_filter_coeff": 1.5}
# This sets the update rate and planning group name for the acceleration limiting filter.
acceleration_filter_update_period = {"update_period": 0.01}
planning_group_name = {"planning_group_name": "panda_arm"}

# ros2_control using FakeSystem as hardware
ros2_controllers_path = os.path.join(
Expand Down Expand Up @@ -91,7 +92,8 @@ def generate_test_description():
),
parameters=[
servo_params,
low_pass_filter_coeff,
acceleration_filter_update_period,
planning_group_name,
moveit_config.robot_description,
moveit_config.robot_description_semantic,
moveit_config.robot_description_kinematics,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,9 @@ def generate_test_description():
.to_dict()
}

# This filter parameter should be >1. Increase it for greater smoothing but slower motion.
low_pass_filter_coeff = {"butterworth_filter_coeff": 1.5}
# This sets the update rate and planning group name for the acceleration limiting filter.
acceleration_filter_update_period = {"update_period": 0.01}
planning_group_name = {"planning_group_name": "panda_arm"}

# ros2_control using FakeSystem as hardware
ros2_controllers_path = os.path.join(
Expand Down Expand Up @@ -82,7 +83,8 @@ def generate_test_description():
name="servo_node",
parameters=[
servo_params,
low_pass_filter_coeff,
acceleration_filter_update_period,
planning_group_name,
moveit_config.robot_description,
moveit_config.robot_description_semantic,
moveit_config.robot_description_kinematics,
Expand Down Expand Up @@ -112,7 +114,8 @@ def generate_test_description():
name="servo_node",
parameters=[
servo_params,
low_pass_filter_coeff,
acceleration_filter_update_period,
planning_group_name,
moveit_config.robot_description,
moveit_config.robot_description_semantic,
moveit_config.robot_description_kinematics,
Expand Down
6 changes: 3 additions & 3 deletions moveit_ros/moveit_servo/tests/test_ros_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ TEST_F(ServoRosFixture, testJointJog)

// Call input type service
auto request = std::make_shared<moveit_msgs::srv::ServoCommandType::Request>();
request->command_type = 0;
request->command_type = moveit_msgs::srv::ServoCommandType::Request::JOINT_JOG;
auto response = switch_input_client_->async_send_request(request);
ASSERT_EQ(response.get()->success, true);

Expand Down Expand Up @@ -116,7 +116,7 @@ TEST_F(ServoRosFixture, testTwist)
"/servo_node/delta_twist_cmds", rclcpp::SystemDefaultsQoS());

auto request = std::make_shared<moveit_msgs::srv::ServoCommandType::Request>();
request->command_type = 1;
request->command_type = moveit_msgs::srv::ServoCommandType::Request::TWIST;
auto response = switch_input_client_->async_send_request(request);
ASSERT_EQ(response.get()->success, true);

Expand Down Expand Up @@ -155,7 +155,7 @@ TEST_F(ServoRosFixture, testPose)
"/servo_node/pose_target_cmds", rclcpp::SystemDefaultsQoS());

auto request = std::make_shared<moveit_msgs::srv::ServoCommandType::Request>();
request->command_type = 2;
request->command_type = moveit_msgs::srv::ServoCommandType::Request::POSE;
auto response = switch_input_client_->async_send_request(request);
ASSERT_EQ(response.get()->success, true);

Expand Down
Loading