Skip to content

Commit

Permalink
bug fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
ARK3r committed Sep 21, 2023
1 parent adcba1e commit de2d3c9
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 28 deletions.
46 changes: 20 additions & 26 deletions example_11/hardware/carlikebot_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,23 +233,20 @@ CarlikeBotSystemHardware::export_command_interfaces()
hardware_interface::CallbackReturn CarlikeBotSystemHardware::on_activate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
if (m_running_simulation)
{
RCLCPP_INFO(rclcpp::get_logger("CarlikeBotSystemHardware"), "Activating ...please wait...");
RCLCPP_INFO(rclcpp::get_logger("CarlikeBotSystemHardware"), "Activating ...please wait...");

for (auto i = 0; i < hw_start_sec_; i++)
{
rclcpp::sleep_for(std::chrono::seconds(1));
RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "%.1f seconds left...", hw_start_sec_ - i);
}
for (auto i = 0; i < hw_start_sec_; i++)
{
rclcpp::sleep_for(std::chrono::seconds(1));
RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "%.1f seconds left...", hw_start_sec_ - i);
}

for (uint i = 0; i < hw_positions_.size(); i++)
{
hw_positions_[i] = 0.0;
hw_velocities_[i] = 0.0;
hw_commands_[i] = 0.0;
}
for (uint i = 0; i < hw_positions_.size(); i++)
{
hw_positions_[i] = 0.0;
hw_velocities_[i] = 0.0;
hw_commands_[i] = 0.0;
}

RCLCPP_INFO(rclcpp::get_logger("CarlikeBotSystemHardware"), "Successfully activated!");
Expand All @@ -260,19 +257,16 @@ hardware_interface::CallbackReturn CarlikeBotSystemHardware::on_activate(
hardware_interface::CallbackReturn CarlikeBotSystemHardware::on_deactivate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
if (m_running_simulation)
{
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(rclcpp::get_logger("CarlikeBotSystemHardware"), "Deactivating ...please wait...");
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(rclcpp::get_logger("CarlikeBotSystemHardware"), "Deactivating ...please wait...");

for (auto i = 0; i < hw_stop_sec_; i++)
{
rclcpp::sleep_for(std::chrono::seconds(1));
RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "%.1f seconds left...", hw_stop_sec_ - i);
}
// END: This part here is for exemplary purposes - Please do not copy to your production code
for (auto i = 0; i < hw_stop_sec_; i++)
{
rclcpp::sleep_for(std::chrono::seconds(1));
RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "%.1f seconds left...", hw_stop_sec_ - i);
}
// END: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(rclcpp::get_logger("CarlikeBotSystemHardware"), "Successfully deactivated!");

return hardware_interface::CallbackReturn::SUCCESS;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,6 @@ class CarlikeBotSystemHardware : public hardware_interface::SystemInterface
const rclcpp::Time & time, const rclcpp::Duration & period) override;

private:
// Parameter disnguishing between simulation and physical robot
bool m_running_simulation;

// Parameters for the CarlikeBot simulation
double hw_start_sec_;
Expand Down

0 comments on commit de2d3c9

Please sign in to comment.