Skip to content

Commit

Permalink
Change use_eth_lib to constexpr
Browse files Browse the repository at this point in the history
  • Loading branch information
rajat2004 committed Dec 10, 2021
1 parent 22b7675 commit bbb1806
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ class PIDPositionController

private:
GeodeticConverter geodetic_converter_;
const bool use_eth_lib_for_geodetic_conv_;
static constexpr bool use_eth_lib_for_geodetic_conv_ = true;

ros::NodeHandle nh_;
ros::NodeHandle nh_private_;
Expand Down
6 changes: 3 additions & 3 deletions ros/src/airsim_ros_pkgs/src/pd_position_controller_simple.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ bool DynamicConstraints::load_from_rosparams(const ros::NodeHandle& nh)
}

PIDPositionController::PIDPositionController(const ros::NodeHandle& nh, const ros::NodeHandle& nh_private)
: use_eth_lib_for_geodetic_conv_(true), nh_(nh), nh_private_(nh_private), has_home_geo_(false), reached_goal_(false), has_goal_(false), has_odom_(false), got_goal_once_(false)
: nh_(nh), nh_private_(nh_private), has_home_geo_(false), reached_goal_(false), has_goal_(false), has_odom_(false), got_goal_once_(false)
{
params_.load_from_rosparams(nh_private_);
constraints_.load_from_rosparams(nh_);
Expand Down Expand Up @@ -177,7 +177,7 @@ bool PIDPositionController::gps_goal_srv_cb(airsim_ros_pkgs::SetGPSPosition::Req
if (!has_goal_) {
msr::airlib::GeoPoint goal_gps_point(request.latitude, request.longitude, request.altitude);
msr::airlib::GeoPoint gps_home(gps_home_msg_.latitude, gps_home_msg_.longitude, gps_home_msg_.altitude);
if (use_eth_lib_for_geodetic_conv_) {
if constexpr (use_eth_lib_for_geodetic_conv_) {
// double initial_latitude, initial_longitude;
// float initial_altitude;
// geodetic_converter_.getHome(&initial_latitude, &initial_longitude, &initial_altitude);
Expand Down Expand Up @@ -226,7 +226,7 @@ bool PIDPositionController::gps_goal_srv_override_cb(airsim_ros_pkgs::SetGPSPosi

msr::airlib::GeoPoint goal_gps_point(request.latitude, request.longitude, request.altitude);
msr::airlib::GeoPoint gps_home(gps_home_msg_.latitude, gps_home_msg_.longitude, gps_home_msg_.altitude);
if (use_eth_lib_for_geodetic_conv_) {
if constexpr (use_eth_lib_for_geodetic_conv_) {
// double initial_latitude, initial_longitude;
// float initial_altitude;
// geodetic_converter_.getHome(&initial_latitude, &initial_longitude, &initial_altitude);
Expand Down

0 comments on commit bbb1806

Please sign in to comment.