1616
1717#include < chrono>
1818#include < cmath>
19+ #include < iomanip>
1920#include < limits>
2021#include < memory>
22+ #include < sstream>
23+ #include < string>
2124#include < vector>
2225
2326#include " hardware_interface/types/hardware_interface_type_values.hpp"
@@ -34,6 +37,9 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_init(
3437 {
3538 return hardware_interface::CallbackReturn::ERROR;
3639 }
40+ logger_ = std::make_shared<rclcpp::Logger>(
41+ rclcpp::get_logger (" controller_manager.resource_manager.hardware_component.system.RRBot" ));
42+ clock_ = std::make_shared<rclcpp::Clock>(rclcpp::Clock ());
3743
3844 // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
3945 hw_start_sec_ = stod (info_.hardware_parameters [" example_param_hw_start_duration_sec" ]);
@@ -49,35 +55,32 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_init(
4955 if (joint.command_interfaces .size () != 1 )
5056 {
5157 RCLCPP_FATAL (
52- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ),
53- " Joint '%s' has %zu command interfaces found. 1 expected." , joint.name .c_str (),
54- joint.command_interfaces .size ());
58+ get_logger (), " Joint '%s' has %zu command interfaces found. 1 expected." ,
59+ joint.name .c_str (), joint.command_interfaces .size ());
5560 return hardware_interface::CallbackReturn::ERROR;
5661 }
5762
5863 if (joint.command_interfaces [0 ].name != hardware_interface::HW_IF_POSITION)
5964 {
6065 RCLCPP_FATAL (
61- rclcpp:: get_logger (" RRBotSystemPositionOnlyHardware " ) ,
62- " Joint '%s' have %s command interfaces found. '%s' expected. " , joint.name .c_str (),
63- joint. command_interfaces [ 0 ]. name . c_str (), hardware_interface::HW_IF_POSITION);
66+ get_logger (), " Joint '%s' have %s command interfaces found. '%s' expected. " ,
67+ joint. name . c_str () , joint. command_interfaces [ 0 ] .name .c_str (),
68+ hardware_interface::HW_IF_POSITION);
6469 return hardware_interface::CallbackReturn::ERROR;
6570 }
6671
6772 if (joint.state_interfaces .size () != 1 )
6873 {
6974 RCLCPP_FATAL (
70- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ),
71- " Joint '%s' has %zu state interface. 1 expected." , joint.name .c_str (),
75+ get_logger (), " Joint '%s' has %zu state interface. 1 expected." , joint.name .c_str (),
7276 joint.state_interfaces .size ());
7377 return hardware_interface::CallbackReturn::ERROR;
7478 }
7579
7680 if (joint.state_interfaces [0 ].name != hardware_interface::HW_IF_POSITION)
7781 {
7882 RCLCPP_FATAL (
79- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ),
80- " Joint '%s' have %s state interface. '%s' expected." , joint.name .c_str (),
83+ get_logger (), " Joint '%s' have %s state interface. '%s' expected." , joint.name .c_str (),
8184 joint.state_interfaces [0 ].name .c_str (), hardware_interface::HW_IF_POSITION);
8285 return hardware_interface::CallbackReturn::ERROR;
8386 }
@@ -90,15 +93,12 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_configure
9093 const rclcpp_lifecycle::State & /* previous_state*/ )
9194{
9295 // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
93- RCLCPP_INFO (
94- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " Configuring ...please wait..." );
96+ RCLCPP_INFO (get_logger (), " Configuring ...please wait..." );
9597
9698 for (int i = 0 ; i < hw_start_sec_; i++)
9799 {
98100 rclcpp::sleep_for (std::chrono::seconds (1 ));
99- RCLCPP_INFO (
100- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " %.1f seconds left..." ,
101- hw_start_sec_ - i);
101+ RCLCPP_INFO (get_logger (), " %.1f seconds left..." , hw_start_sec_ - i);
102102 }
103103 // END: This part here is for exemplary purposes - Please do not copy to your production code
104104
@@ -108,8 +108,7 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_configure
108108 hw_states_[i] = 0 ;
109109 hw_commands_[i] = 0 ;
110110 }
111-
112- RCLCPP_INFO (rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " Successfully configured!" );
111+ RCLCPP_INFO (get_logger (), " Successfully configured!" );
113112
114113 return hardware_interface::CallbackReturn::SUCCESS;
115114}
@@ -144,15 +143,12 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_activate(
144143 const rclcpp_lifecycle::State & /* previous_state*/ )
145144{
146145 // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
147- RCLCPP_INFO (
148- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " Activating ...please wait..." );
146+ RCLCPP_INFO (get_logger (), " Activating ...please wait..." );
149147
150148 for (int i = 0 ; i < hw_start_sec_; i++)
151149 {
152150 rclcpp::sleep_for (std::chrono::seconds (1 ));
153- RCLCPP_INFO (
154- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " %.1f seconds left..." ,
155- hw_start_sec_ - i);
151+ RCLCPP_INFO (get_logger (), " %.1f seconds left..." , hw_start_sec_ - i);
156152 }
157153 // END: This part here is for exemplary purposes - Please do not copy to your production code
158154
@@ -162,7 +158,7 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_activate(
162158 hw_commands_[i] = hw_states_[i];
163159 }
164160
165- RCLCPP_INFO (rclcpp:: get_logger (" RRBotSystemPositionOnlyHardware " ), " Successfully activated!" );
161+ RCLCPP_INFO (get_logger (), " Successfully activated!" );
166162
167163 return hardware_interface::CallbackReturn::SUCCESS;
168164}
@@ -171,18 +167,15 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_deactivat
171167 const rclcpp_lifecycle::State & /* previous_state*/ )
172168{
173169 // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
174- RCLCPP_INFO (
175- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " Deactivating ...please wait..." );
170+ RCLCPP_INFO (get_logger (), " Deactivating ...please wait..." );
176171
177172 for (int i = 0 ; i < hw_stop_sec_; i++)
178173 {
179174 rclcpp::sleep_for (std::chrono::seconds (1 ));
180- RCLCPP_INFO (
181- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " %.1f seconds left..." ,
182- hw_stop_sec_ - i);
175+ RCLCPP_INFO (get_logger (), " %.1f seconds left..." , hw_stop_sec_ - i);
183176 }
184177
185- RCLCPP_INFO (rclcpp:: get_logger (" RRBotSystemPositionOnlyHardware " ), " Successfully deactivated!" );
178+ RCLCPP_INFO (get_logger (), " Successfully deactivated!" );
186179 // END: This part here is for exemplary purposes - Please do not copy to your production code
187180
188181 return hardware_interface::CallbackReturn::SUCCESS;
@@ -192,17 +185,18 @@ hardware_interface::return_type RRBotSystemPositionOnlyHardware::read(
192185 const rclcpp::Time & /* time*/ , const rclcpp::Duration & /* period*/ )
193186{
194187 // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
195- RCLCPP_INFO (rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " Reading..." );
188+ std::stringstream ss;
189+ ss << " Reading states:" ;
196190
197191 for (uint i = 0 ; i < hw_states_.size (); i++)
198192 {
199193 // Simulate RRBot's movement
200194 hw_states_[i] = hw_states_[i] + (hw_commands_[i] - hw_states_[i]) / hw_slowdown_;
201- RCLCPP_INFO (
202- rclcpp::get_logger ( " RRBotSystemPositionOnlyHardware " ), " Got state %.5f for joint %d! " ,
203- hw_states_[i], i) ;
195+
196+ ss << std::fixed << std::setprecision ( 2 ) << std::endl
197+ << " \t " << hw_states_[i] << " for joint ' " << info_. joints [i]. name << " ' " ;
204198 }
205- RCLCPP_INFO ( rclcpp:: get_logger (" RRBotSystemPositionOnlyHardware " ), " Joints successfully read! " );
199+ RCLCPP_INFO_THROTTLE ( get_logger (), * get_clock (), 500 , " %s " , ss. str (). c_str () );
206200 // END: This part here is for exemplary purposes - Please do not copy to your production code
207201
208202 return hardware_interface::return_type::OK;
@@ -212,17 +206,16 @@ hardware_interface::return_type RRBotSystemPositionOnlyHardware::write(
212206 const rclcpp::Time & /* time*/ , const rclcpp::Duration & /* period*/ )
213207{
214208 // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
215- RCLCPP_INFO (rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " Writing..." );
209+ std::stringstream ss;
210+ ss << " Writing commands:" ;
216211
217212 for (uint i = 0 ; i < hw_commands_.size (); i++)
218213 {
219214 // Simulate sending commands to the hardware
220- RCLCPP_INFO (
221- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " Got command %.5f for joint %d!" ,
222- hw_commands_[i], i);
215+ ss << std::fixed << std::setprecision (2 ) << std::endl
216+ << " \t " << hw_commands_[i] << " for joint '" << info_.joints [i].name << " '" ;
223217 }
224- RCLCPP_INFO (
225- rclcpp::get_logger (" RRBotSystemPositionOnlyHardware" ), " Joints successfully written!" );
218+ RCLCPP_INFO_THROTTLE (get_logger (), *get_clock (), 500 , " %s" , ss.str ().c_str ());
226219 // END: This part here is for exemplary purposes - Please do not copy to your production code
227220
228221 return hardware_interface::return_type::OK;
0 commit comments