Skip to content
Closed
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
51 changes: 29 additions & 22 deletions diff_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
controller_interface
generate_parameter_library
geometry_msgs
hardware_interface
nav_msgs
Expand All @@ -30,30 +31,27 @@ foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

add_library(${PROJECT_NAME} SHARED
generate_parameter_library(diff_drive_controller_parameters
src/diff_drive_controller_parameter.yaml
)

add_library(diff_drive_controller SHARED
src/diff_drive_controller.cpp
src/odometry.cpp
src/speed_limiter.cpp
)
target_include_directories(${PROJECT_NAME}
target_include_directories(diff_drive_controller
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_target_dependencies(diff_drive_controller ${THIS_PACKAGE_INCLUDE_DEPENDS})
target_link_libraries(diff_drive_controller
diff_drive_controller_parameters
)
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(${PROJECT_NAME} PRIVATE "DIFF_DRIVE_CONTROLLER_BUILDING_DLL")
target_compile_definitions(diff_drive_controller PRIVATE "DIFF_DRIVE_CONTROLLER_BUILDING_DLL")
pluginlib_export_plugin_description_file(controller_interface diff_drive_plugin.xml)

install(DIRECTORY include/
DESTINATION include
)

install(TARGETS ${PROJECT_NAME}
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
)

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(controller_manager REQUIRED)
Expand All @@ -64,7 +62,7 @@ if(BUILD_TESTING)
ENV config_file=${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_diff_drive_controller.yaml)
target_include_directories(test_diff_drive_controller PRIVATE include)
target_link_libraries(test_diff_drive_controller
${PROJECT_NAME}
diff_drive_controller
)

ament_target_dependencies(test_diff_drive_controller
Expand All @@ -90,13 +88,22 @@ if(BUILD_TESTING)

endif()

ament_export_dependencies(
${THIS_PACKAGE_INCLUDE_DEPENDS}
)
ament_export_include_directories(
include
install(
DIRECTORY include/
DESTINATION include
)
ament_export_libraries(
${PROJECT_NAME}

install(
TARGETS
diff_drive_controller
diff_drive_controller_parameters
EXPORT export_diff_drive_controller
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
INCLUDES DESTINATION include
)

ament_export_targets(export_diff_drive_controller HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,9 @@
#include "realtime_tools/realtime_publisher.h"
#include "tf2_msgs/msg/tf_message.hpp"

#include "diff_drive_controller_parameters.hpp"


namespace diff_drive_controller
{
class DiffDriveController : public controller_interface::ControllerInterface
Expand Down Expand Up @@ -101,35 +104,21 @@ class DiffDriveController : public controller_interface::ControllerInterface
const std::string & side, const std::vector<std::string> & wheel_names,
std::vector<WheelHandle> & registered_handles);

std::vector<std::string> left_wheel_names_;
std::vector<std::string> right_wheel_names_;
// std::vector<std::string> left_wheel_names_;
// std::vector<std::string> right_wheel_names_;
Comment on lines -104 to +108
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why did we leave these commented out?


std::vector<WheelHandle> registered_left_wheel_handles_;
std::vector<WheelHandle> registered_right_wheel_handles_;

struct WheelParams
{
size_t wheels_per_side = 0;
double separation = 0.0; // w.r.t. the midpoint of the wheel width
double radius = 0.0; // Assumed to be the same for both wheels
double separation_multiplier = 1.0;
double left_radius_multiplier = 1.0;
double right_radius_multiplier = 1.0;
} wheel_params_;

struct OdometryParams
{
bool open_loop = false;
bool position_feedback = true;
bool enable_odom_tf = true;
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_;
// Parameters from ROS for diff_drive_controller
std::shared_ptr<ParamListener> param_listener_;
Params params_;

Odometry odometry_;

// Timeout to consider cmd_vel commands old
std::chrono::milliseconds cmd_vel_timeout_{500};

std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
realtime_odometry_publisher_ = nullptr;
Expand All @@ -139,8 +128,6 @@ class DiffDriveController : public controller_interface::ControllerInterface
std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
realtime_odometry_transform_publisher_ = nullptr;

// Timeout to consider cmd_vel commands old
std::chrono::milliseconds cmd_vel_timeout_{500};

bool subscriber_is_active_ = false;
rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ = nullptr;
Expand Down
1 change: 1 addition & 0 deletions diff_drive_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>controller_interface</depend>
<depend>generate_parameter_library</depend>
<depend>geometry_msgs</depend>
<depend>hardware_interface</depend>
<depend>nav_msgs</depend>
Expand Down
Loading