@@ -233,23 +233,20 @@ CarlikeBotSystemHardware::export_command_interfaces()
233
233
hardware_interface::CallbackReturn CarlikeBotSystemHardware::on_activate (
234
234
const rclcpp_lifecycle::State & /* previous_state*/ )
235
235
{
236
- if (m_running_simulation)
237
- {
238
- RCLCPP_INFO (rclcpp::get_logger (" CarlikeBotSystemHardware" ), " Activating ...please wait..." );
236
+ RCLCPP_INFO (rclcpp::get_logger (" CarlikeBotSystemHardware" ), " Activating ...please wait..." );
239
237
240
- for (auto i = 0 ; i < hw_start_sec_; i++)
241
- {
242
- rclcpp::sleep_for (std::chrono::seconds (1 ));
243
- RCLCPP_INFO (
244
- rclcpp::get_logger (" CarlikeBotSystemHardware" ), " %.1f seconds left..." , hw_start_sec_ - i);
245
- }
238
+ for (auto i = 0 ; i < hw_start_sec_; i++)
239
+ {
240
+ rclcpp::sleep_for (std::chrono::seconds (1 ));
241
+ RCLCPP_INFO (
242
+ rclcpp::get_logger (" CarlikeBotSystemHardware" ), " %.1f seconds left..." , hw_start_sec_ - i);
243
+ }
246
244
247
- for (uint i = 0 ; i < hw_positions_.size (); i++)
248
- {
249
- hw_positions_[i] = 0.0 ;
250
- hw_velocities_[i] = 0.0 ;
251
- hw_commands_[i] = 0.0 ;
252
- }
245
+ for (uint i = 0 ; i < hw_positions_.size (); i++)
246
+ {
247
+ hw_positions_[i] = 0.0 ;
248
+ hw_velocities_[i] = 0.0 ;
249
+ hw_commands_[i] = 0.0 ;
253
250
}
254
251
255
252
RCLCPP_INFO (rclcpp::get_logger (" CarlikeBotSystemHardware" ), " Successfully activated!" );
@@ -260,19 +257,16 @@ hardware_interface::CallbackReturn CarlikeBotSystemHardware::on_activate(
260
257
hardware_interface::CallbackReturn CarlikeBotSystemHardware::on_deactivate (
261
258
const rclcpp_lifecycle::State & /* previous_state*/ )
262
259
{
263
- if (m_running_simulation)
264
- {
265
- // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
266
- RCLCPP_INFO (rclcpp::get_logger (" CarlikeBotSystemHardware" ), " Deactivating ...please wait..." );
260
+ // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
261
+ RCLCPP_INFO (rclcpp::get_logger (" CarlikeBotSystemHardware" ), " Deactivating ...please wait..." );
267
262
268
- for (auto i = 0 ; i < hw_stop_sec_; i++)
269
- {
270
- rclcpp::sleep_for (std::chrono::seconds (1 ));
271
- RCLCPP_INFO (
272
- rclcpp::get_logger (" CarlikeBotSystemHardware" ), " %.1f seconds left..." , hw_stop_sec_ - i);
273
- }
274
- // END: This part here is for exemplary purposes - Please do not copy to your production code
263
+ for (auto i = 0 ; i < hw_stop_sec_; i++)
264
+ {
265
+ rclcpp::sleep_for (std::chrono::seconds (1 ));
266
+ RCLCPP_INFO (
267
+ rclcpp::get_logger (" CarlikeBotSystemHardware" ), " %.1f seconds left..." , hw_stop_sec_ - i);
275
268
}
269
+ // END: This part here is for exemplary purposes - Please do not copy to your production code
276
270
RCLCPP_INFO (rclcpp::get_logger (" CarlikeBotSystemHardware" ), " Successfully deactivated!" );
277
271
278
272
return hardware_interface::CallbackReturn::SUCCESS;
0 commit comments