Skip to content

Commit 7550a71

Browse files
Fix compiler warnings (#674)
1 parent 3ef7b70 commit 7550a71

File tree

1 file changed

+3
-2
lines changed

1 file changed

+3
-2
lines changed

gz_ros2_control/src/gz_ros2_control_plugin.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -171,7 +171,7 @@ class GazeboSimROS2ControlPluginPrivate
171171

172172
/// \brief Last time the update method was called
173173
rclcpp::Time last_update_sim_time_ros_ =
174-
rclcpp::Time((int64_t)0, RCL_ROS_TIME);
174+
rclcpp::Time(static_cast<int64_t>(0), RCL_ROS_TIME);
175175

176176
/// \brief ECM pointer
177177
sim::EntityComponentManager * ecm{nullptr};
@@ -458,7 +458,8 @@ void GazeboSimROS2ControlPlugin::Configure(
458458
this->dataPtr->node_->get_namespace(), options));
459459
this->dataPtr->executor_->add_node(this->dataPtr->controller_manager_);
460460

461-
this->dataPtr->update_rate = this->dataPtr->controller_manager_->get_update_rate();
461+
this->dataPtr->update_rate =
462+
static_cast<int>(this->dataPtr->controller_manager_->get_update_rate());
462463
this->dataPtr->control_period_ = rclcpp::Duration(
463464
std::chrono::duration_cast<std::chrono::nanoseconds>(
464465
std::chrono::duration<double>(1.0 / static_cast<double>(this->dataPtr->update_rate))));

0 commit comments

Comments
 (0)