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

[tricycle_controller] Use generate_parameter_library #957

Merged
merged 5 commits into from
Jan 29, 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
13 changes: 10 additions & 3 deletions tricycle_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
builtin_interfaces
controller_interface
geometry_msgs
generate_parameter_library
hardware_interface
nav_msgs
pluginlib
Expand All @@ -29,6 +30,10 @@ foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

generate_parameter_library(tricycle_controller_parameters
src/tricycle_controller_parameter.yaml
)

add_library(tricycle_controller SHARED
src/tricycle_controller.cpp
src/odometry.cpp
Expand All @@ -40,6 +45,7 @@ target_include_directories(tricycle_controller PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/tricycle_controller>
)
target_link_libraries(tricycle_controller PUBLIC tricycle_controller_parameters)
ament_target_dependencies(tricycle_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

pluginlib_export_plugin_description_file(controller_interface tricycle_controller.xml)
Expand All @@ -50,8 +56,7 @@ if(BUILD_TESTING)
find_package(ros2_control_test_assets REQUIRED)

ament_add_gmock(test_tricycle_controller
test/test_tricycle_controller.cpp
ENV config_file=${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_tricycle_controller.yaml)
test/test_tricycle_controller.cpp)
target_link_libraries(test_tricycle_controller
tricycle_controller
)
Expand All @@ -66,8 +71,9 @@ if(BUILD_TESTING)
tf2_msgs
)

ament_add_gmock(test_load_tricycle_controller
add_rostest_with_parameters_gmock(test_load_tricycle_controller
test/test_load_tricycle_controller.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_tricycle_controller.yaml
)
target_link_libraries(test_load_tricycle_controller
tricycle_controller
Expand All @@ -85,6 +91,7 @@ install(
install(
TARGETS
tricycle_controller
tricycle_controller_parameters
EXPORT export_tricycle_controller
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
Expand Down
10 changes: 9 additions & 1 deletion tricycle_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@
tricycle_controller
=====================

Controller for mobile robots with tricycle drive.
Controller for mobile robots with a single double-actuated wheel, including traction and steering. An example is a tricycle robot with the actuated wheel in the front and two trailing wheels on the rear axle.

Input for control are robot base_link twist commands which are translated to traction and steering
commands for the tricycle drive base. Odometry is computed from hardware feedback and published.

Expand All @@ -24,3 +25,10 @@ Other features
Odometry publishing
Velocity, acceleration and jerk limits
Automatic stop after command timeout

Parameters
--------------

This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

.. generate_parameter_library_details:: ../src/tricycle_controller_parameter.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,9 @@
#include "tricycle_controller/traction_limiter.hpp"
#include "tricycle_controller/visibility_control.h"

// auto-generated by generate_parameter_library
#include "tricycle_controller_parameters.hpp"

namespace tricycle_controller
{
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
Expand Down Expand Up @@ -109,31 +112,14 @@ class TricycleController : public controller_interface::ControllerInterface
double convert_trans_rot_vel_to_steering_angle(double v, double omega, double wheelbase);
std::tuple<double, double> twist_to_ackermann(double linear_command, double angular_command);

std::string traction_joint_name_;
std::string steering_joint_name_;
// Parameters from ROS for tricycle_controller
std::shared_ptr<ParamListener> param_listener_;
Params params_;

// HACK: put into vector to avoid initializing structs because they have no default constructors
std::vector<TractionHandle> traction_joint_;
std::vector<SteeringHandle> steering_joint_;

struct WheelParams
{
double wheelbase = 0.0;
double radius = 0.0;
} wheel_params_;

struct OdometryParams
{
bool open_loop = false;
bool enable_odom_tf = false;
bool odom_only_twist = false; // for doing the pose integration in separate node
std::string base_frame_id = "base_link";
std::string odom_frame_id = "odom";
std::array<double, 6> pose_covariance_diagonal;
std::array<double, 6> twist_covariance_diagonal;
} odom_params_;

bool publish_ackermann_command_ = false;
std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ = nullptr;
std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
realtime_ackermann_command_publisher_ = nullptr;
Expand Down Expand Up @@ -168,7 +154,6 @@ class TricycleController : public controller_interface::ControllerInterface
SteeringLimiter limiter_steering_;

bool is_halted = false;
bool use_stamped_vel_ = true;

void reset_odometry(
const std::shared_ptr<rmw_request_id_t> request_header,
Expand Down
1 change: 1 addition & 0 deletions tricycle_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<author email="tony.najjar@logivations.com">Tony Najjar</author>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>generate_parameter_library</build_depend>

<depend>ackermann_msgs</depend>
<depend>backward_ros</depend>
Expand Down
Loading
Loading