Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix various inconsistencies, warnings #2485

Merged
merged 4 commits into from
Apr 1, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
33 changes: 5 additions & 28 deletions AirLib/include/vehicles/car/firmwares/ardurover/ArduRoverApi.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,27 +148,6 @@ class ArduRoverApi : public CarApiBase {
udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port);
}

const GpsBase* getGps() const
{
return static_cast<const GpsBase*>(sensors_->getByType(SensorBase::SensorType::Gps));
}
const ImuBase* getImu() const
{
return static_cast<const ImuBase*>(sensors_->getByType(SensorBase::SensorType::Imu));
}
const MagnetometerBase* getMagnetometer() const
{
return static_cast<const MagnetometerBase*>(sensors_->getByType(SensorBase::SensorType::Magnetometer));
}
const BarometerBase* getBarometer() const
{
return static_cast<const BarometerBase*>(sensors_->getByType(SensorBase::SensorType::Barometer));
}
const LidarBase* getLidar() const
{
return static_cast<const LidarBase*>(sensors_->getByType(SensorBase::SensorType::Lidar));
}

private:
void recvRoverControl()
{
Expand Down Expand Up @@ -202,18 +181,16 @@ class ArduRoverApi : public CarApiBase {
if (sensors_ == nullptr)
return;

const auto& gps_output = getGps()->getOutput();
const auto& imu_output = getImu()->getOutput();
// const auto& baro_output = getBarometer()->getOutput();
// const auto& mag_output = getMagnetometer()->getOutput();
const auto& gps_output = getGpsData("");
const auto& imu_output = getImuData("");

std::ostringstream oss;

const auto lidar = getLidar();
const uint count_lidars = getSensors().size(SensorBase::SensorType::Lidar);
// TODO: Add bool value in settings to check whether to send lidar data or not
// Since it's possible that we don't want to send the lidar data to Ardupilot but still have the lidar (maybe as a ROS topic)
if (lidar != nullptr) {
const auto& lidar_output = lidar->getOutput();
if (count_lidars != 0) {
const auto& lidar_output = getLidarData("");
oss << ","
"\"lidar\": {"
"\"point_cloud\": [";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class ArduCopterApi : public MultirotorApiBase {

public:
ArduCopterApi(const MultiRotorParams* vehicle_params, const AirSimSettings::MavLinkConnectionInfo& connection_info)
: ip(connection_info.udp_address), vehicle_params_(vehicle_params)
: ip_(connection_info.udp_address), vehicle_params_(vehicle_params)
{
connection_info_ = connection_info;
sensors_ = &getSensors();
Expand Down Expand Up @@ -71,22 +71,25 @@ class ArduCopterApi : public MultirotorApiBase {
Utils::log("Not Implemented: isApiControlEnabled", Utils::kLogLevelInfo);
return false;
}
virtual void enableApiControl(bool) override
virtual void enableApiControl(bool is_enabled) override
{
Utils::log("Not Implemented: enableApiControl", Utils::kLogLevelInfo);
unused(is_enabled);
}
virtual bool armDisarm(bool) override
virtual bool armDisarm(bool arm) override
{
Utils::log("Not Implemented: armDisarm", Utils::kLogLevelInfo);
unused(arm);
return false;
}
virtual GeoPoint getHomeGeoPoint() const override
{
Utils::log("Not Implemented: getHomeGeoPoint", Utils::kLogLevelInfo);
return GeoPoint(Utils::nan<double>(), Utils::nan<double>(), Utils::nan<float>());
}
virtual void getStatusMessages(std::vector<std::string>&) override
virtual void getStatusMessages(std::vector<std::string>& messages) override
{
unused(messages);
}

virtual const SensorCollection& getSensors() const override
Expand All @@ -99,21 +102,28 @@ class ArduCopterApi : public MultirotorApiBase {
{
return rotor_controls_[rotor_index];
}

virtual size_t getActuatorCount() const override
{
return vehicle_params_->getParams().rotor_count;
}

virtual void moveByRC(const RCData& rc_data) override
{
setRCData(rc_data);
}
virtual void setSimulatedGroundTruth(const Kinematics::State*, const Environment*) override

virtual void setSimulatedGroundTruth(const Kinematics::State* kinematics, const Environment* environment) override
{
Utils::log("Not Implemented: setSimulatedGroundTruth", Utils::kLogLevelInfo);
unused(kinematics);
unused(environment);
}

virtual bool setRCData(const RCData& rc_data) override
{
last_rcData_ = rc_data;
is_rc_connected = true;
is_rc_connected_ = true;

return true;
}
Expand Down Expand Up @@ -295,46 +305,25 @@ class ArduCopterApi : public MultirotorApiBase {

void connect()
{
port = static_cast<uint16_t>(connection_info_.udp_port);
port_ = static_cast<uint16_t>(connection_info_.udp_port);

closeConnections();

if (ip == "") {
if (ip_ == "") {
throw std::invalid_argument("UdpIp setting is invalid.");
}

if (port == 0) {
if (port_ == 0) {
throw std::invalid_argument("UdpPort setting has an invalid value.");
}

Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", port, connection_info_.local_host_ip.c_str(), ip.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port, connection_info_.local_host_ip.c_str(), ip.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", port_, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo);

udpSocket_ = std::make_shared<mavlinkcom::UdpSocket>();
udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port);
}

const GpsBase* getGps() const
{
return static_cast<const GpsBase*>(sensors_->getByType(SensorBase::SensorType::Gps));
}
const ImuBase* getImu() const
{
return static_cast<const ImuBase*>(sensors_->getByType(SensorBase::SensorType::Imu));
}
const MagnetometerBase* getMagnetometer() const
{
return static_cast<const MagnetometerBase*>(sensors_->getByType(SensorBase::SensorType::Magnetometer));
}
const BarometerBase* getBarometer() const
{
return static_cast<const BarometerBase*>(sensors_->getByType(SensorBase::SensorType::Barometer));
}
const LidarBase* getLidar() const
{
return static_cast<const LidarBase*>(sensors_->getByType(SensorBase::SensorType::Lidar));
}

private:
virtual void normalizeRotorControls()
{
Expand All @@ -349,15 +338,13 @@ class ArduCopterApi : public MultirotorApiBase {
if (sensors_ == nullptr)
return;

const auto& gps_output = getGps()->getOutput();
const auto& imu_output = getImu()->getOutput();
// const auto& baro_output = getBarometer()->getOutput();
// const auto& mag_output = getMagnetometer()->getOutput();
const auto& gps_output = getGpsData("");
const auto& imu_output = getImuData("");

std::ostringstream oss;

// Send RC channels to Ardupilot if present
if (is_rc_connected && last_rcData_.is_valid) {
if (is_rc_connected_ && last_rcData_.is_valid) {
oss << ","
"\"rc\": {"
"\"channels\": ["
Expand All @@ -372,11 +359,11 @@ class ArduCopterApi : public MultirotorApiBase {
<< "]}";
}

const auto lidar = getLidar();
const uint count_lidars = getSensors().size(SensorBase::SensorType::Lidar);
// TODO: Add bool value in settings to check whether to send lidar data or not
// Since it's possible that we don't want to send the lidar data to Ardupilot but still have the lidar (maybe as a ROS topic)
if (lidar != nullptr) {
const auto& lidar_output = lidar->getOutput();
if (count_lidars != 0) {
const auto& lidar_output = getLidarData("");
oss << ","
"\"lidar\": {"
"\"point_cloud\": [";
Expand Down Expand Up @@ -443,7 +430,7 @@ class ArduCopterApi : public MultirotorApiBase {

// Send data
if (udpSocket_ != nullptr) {
udpSocket_->sendto(buf, strlen(buf), ip, port);
udpSocket_->sendto(buf, strlen(buf), ip_, port_);
}
}

Expand Down Expand Up @@ -479,15 +466,15 @@ class ArduCopterApi : public MultirotorApiBase {
std::shared_ptr<mavlinkcom::UdpSocket> udpSocket_;

AirSimSettings::MavLinkConnectionInfo connection_info_;
uint16_t port;
const std::string& ip;
uint16_t port_;
const std::string& ip_;
const SensorCollection* sensors_;
const MultiRotorParams* vehicle_params_;

MultirotorApiParams safety_params_;

RCData last_rcData_;
bool is_rc_connected;
bool is_rc_connected_;

// TODO: Increase to 6 or 8 for hexa or larger frames, 11 was used in SoloAPI
static const int RotorControlCount = 4;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class ArduCopterParams : public MultiRotorParams {
auto& params = getParams();

// Use connection_info_.model for the model name, see Px4MultiRotorParams for example

// Only Generic for now
setupFrameGenericQuad(params);
}
Expand Down Expand Up @@ -81,8 +81,6 @@ class ArduCopterParams : public MultiRotorParams {
}

AirSimSettings::MavLinkConnectionInfo connection_info_;
vector<unique_ptr<SensorBase>> sensor_storage_;
// const AirSimSettings::MavlinkVehicleSetting* vehicle_setting_; //store as pointer because of derived classes
std::shared_ptr<const SensorFactory> sensor_factory_;
};

Expand Down
Loading