@@ -34,15 +34,15 @@ namespace picknik_twist_controller
3434{
3535using hardware_interface::LoanedCommandInterface;
3636
37- PicknikTwistControler::PicknikTwistControler ()
37+ PicknikTwistController::PicknikTwistController ()
3838: controller_interface::ControllerInterface(),
3939 rt_command_ptr_ (nullptr ),
4040 twist_command_subscriber_(nullptr )
4141{
4242}
4343
4444controller_interface::InterfaceConfiguration
45- PicknikTwistControler ::command_interface_configuration () const
45+ PicknikTwistController ::command_interface_configuration () const
4646{
4747 controller_interface::InterfaceConfiguration command_interfaces_config;
4848 command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
@@ -55,14 +55,14 @@ PicknikTwistControler::command_interface_configuration() const
5555 return command_interfaces_config;
5656}
5757
58- controller_interface::InterfaceConfiguration PicknikTwistControler ::state_interface_configuration ()
58+ controller_interface::InterfaceConfiguration PicknikTwistController ::state_interface_configuration ()
5959 const
6060{
6161 return controller_interface::InterfaceConfiguration{
6262 controller_interface::interface_configuration_type::NONE};
6363}
6464
65- CallbackReturn PicknikTwistControler ::on_init ()
65+ CallbackReturn PicknikTwistController ::on_init ()
6666{
6767 try
6868 {
@@ -79,7 +79,7 @@ CallbackReturn PicknikTwistControler::on_init()
7979 return CallbackReturn::SUCCESS;
8080}
8181
82- CallbackReturn PicknikTwistControler ::on_configure (
82+ CallbackReturn PicknikTwistController ::on_configure (
8383 const rclcpp_lifecycle::State & /* previous_state*/ )
8484{
8585 joint_name_ = get_node ()->get_parameter (" joint" ).as_string ();
@@ -110,23 +110,23 @@ CallbackReturn PicknikTwistControler::on_configure(
110110 return CallbackReturn::SUCCESS;
111111}
112112
113- CallbackReturn PicknikTwistControler ::on_activate (
113+ CallbackReturn PicknikTwistController ::on_activate (
114114 const rclcpp_lifecycle::State & /* previous_state*/ )
115115{
116116 // reset command buffer if a command came through callback when controller was inactive
117117 rt_command_ptr_ = realtime_tools::RealtimeBuffer<std::shared_ptr<CmdType>>(nullptr );
118118 return CallbackReturn::SUCCESS;
119119}
120120
121- CallbackReturn PicknikTwistControler ::on_deactivate (
121+ CallbackReturn PicknikTwistController ::on_deactivate (
122122 const rclcpp_lifecycle::State & /* previous_state*/ )
123123{
124124 // reset command buffer
125125 rt_command_ptr_ = realtime_tools::RealtimeBuffer<std::shared_ptr<CmdType>>(nullptr );
126126 return CallbackReturn::SUCCESS;
127127}
128128
129- controller_interface::return_type PicknikTwistControler ::update (
129+ controller_interface::return_type PicknikTwistController ::update (
130130 const rclcpp::Time & /* time*/ , const rclcpp::Duration & /* period*/ )
131131{
132132 auto twist_commands = rt_command_ptr_.readFromRT ();
@@ -159,4 +159,4 @@ controller_interface::return_type PicknikTwistControler::update(
159159#include " pluginlib/class_list_macros.hpp"
160160
161161PLUGINLIB_EXPORT_CLASS (
162- picknik_twist_controller::PicknikTwistControler , controller_interface::ControllerInterface)
162+ picknik_twist_controller::PicknikTwistController , controller_interface::ControllerInterface)
0 commit comments