15#ifndef VELOCITY_CONTROLLERS__JOINT_GROUP_VELOCITY_CONTROLLER_HPP_
16#define VELOCITY_CONTROLLERS__JOINT_GROUP_VELOCITY_CONTROLLER_HPP_
20#include "forward_command_controller/forward_command_controller.hpp"
21#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
22#include "velocity_controllers/visibility_control.h"
24namespace velocity_controllers
39 VELOCITY_CONTROLLERS_PUBLIC
42 VELOCITY_CONTROLLERS_PUBLIC controller_interface::CallbackReturn
on_init()
override;
44 VELOCITY_CONTROLLERS_PUBLIC
45 controller_interface::CallbackReturn on_deactivate(
46 const rclcpp_lifecycle::State & previous_state)
override;
Forward command controller for a set of joints.
Definition forward_command_controller.hpp:40
Forward command controller for a set of velocity controlled joints (linear or angular).
Definition joint_group_velocity_controller.hpp:37
VELOCITY_CONTROLLERS_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition joint_group_velocity_controller.cpp:31