15#ifndef VELOCITY_CONTROLLERS__JOINT_GROUP_VELOCITY_CONTROLLER_HPP_
16#define VELOCITY_CONTROLLERS__JOINT_GROUP_VELOCITY_CONTROLLER_HPP_
18#include "forward_command_controller/forward_command_controller.hpp"
20namespace velocity_controllers
37 controller_interface::CallbackReturn
on_init()
override;
39 controller_interface::CallbackReturn on_deactivate(
40 const rclcpp_lifecycle::State & previous_state)
override;
Forward command controller for a set of joints.
Definition forward_command_controller.hpp:38
Forward command controller for a set of velocity controlled joints (linear or angular).
Definition joint_group_velocity_controller.hpp:33
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition joint_group_velocity_controller.cpp:30