Skip to content

Commit

Permalink
fix unused params warning
Browse files Browse the repository at this point in the history
  • Loading branch information
andre-nguyen committed May 4, 2017
1 parent 729193b commit 6c4bf1a
Show file tree
Hide file tree
Showing 12 changed files with 53 additions and 1 deletion.
2 changes: 2 additions & 0 deletions AirLib/include/common/StateReporter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ class StateReporter {
//TODO: need better line end handling
void startHeading(string heading, uint heading_size, uint columns = 20)
{
unused(heading_size);
unused(columns);
ss_ << "\n";
ss_ << heading;
}
Expand Down
1 change: 1 addition & 0 deletions AirLib/include/common/UpdatableObject.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ class UpdatableObject {

virtual void reportState(StateReporter& reporter)
{
unused(reporter);
//default implementation doesn't do anything
}

Expand Down
4 changes: 3 additions & 1 deletion AirLib/include/common/common_utils/AsyncTasker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
class AsyncTasker {
public:
AsyncTasker(unsigned int thread_count = 4)
: threads_(thread_count), error_handler_([](std::exception e) {})
: threads_(thread_count), error_handler_([](std::exception e) {unused(e);})
{
}

Expand All @@ -26,6 +26,7 @@ class AsyncTasker {
if (iterations == 1)
{
threads_.push([=](int i) {
unused(i);
try {
func();
}
Expand All @@ -36,6 +37,7 @@ class AsyncTasker {
}
else {
threads_.push([=](int i) {
unused(i);
try {
for (unsigned int itr = 0; itr < iterations; ++itr) {
func();
Expand Down
4 changes: 4 additions & 0 deletions AirLib/include/common/common_utils/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,10 @@ static int _vscprintf(const char * format, va_list pargs)
}
#endif

// Call this on a function parameter to suppress the unused paramter warning
template <class T> inline
void unused(T const & result) { static_cast<void>(result); }

namespace common_utils {

class Utils {
Expand Down
2 changes: 2 additions & 0 deletions AirLib/include/controllers/ControllerBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ class ControllerBase : public UpdatableObject {

virtual void getStatusMessages(std::vector<std::string>& messages)
{
unused(messages);
//default implementation
}

Expand All @@ -46,6 +47,7 @@ class ControllerBase : public UpdatableObject {

virtual void reportTelemetry(float renderTime)
{
unused(renderTime);
//no default action
}

Expand Down
14 changes: 14 additions & 0 deletions AirLib/include/controllers/rosflight/AirSimRosFlightBoard.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,11 @@ class AirSimRosFlightBoard : public rosflight::Board {

virtual void pwmInit(bool useCPPM, bool usePwmFilter, bool fastPWM, uint32_t motorPwmRate, uint16_t idlePulseUsec) override
{
unused(useCPPM);
unused(usePwmFilter);
unused(fastPWM);
unused(motorPwmRate);
unused(idlePulseUsec);
for (uint i = 0; i < OutputMotorCount; ++i)
motors_pwm_[i] = 1000;
for (uint i = 0; i < InputChannelCount; ++i)
Expand All @@ -109,11 +114,14 @@ class AirSimRosFlightBoard : public rosflight::Board {
virtual void set_led(uint8_t index, bool is_on) override
{
//ignored for now
unused(index);
unused(is_on);
}

virtual void toggle_led(uint8_t index) override
{
//ignored for now
unused(index);
}

virtual void init_params() override
Expand All @@ -128,11 +136,13 @@ class AirSimRosFlightBoard : public rosflight::Board {

virtual bool write_params(bool blink_led) override
{
unused(blink_led);
return false;
}

virtual void init_imu(uint16_t& acc1G, float& gyroScale, int boardVersion) override
{
unused(boardVersion);
//same as mpu6050_init
acc1G = kAccelAdcBits;
gyroScale = kGyroScale;
Expand Down Expand Up @@ -173,6 +183,9 @@ class AirSimRosFlightBoard : public rosflight::Board {

virtual void read_diff_pressure(float& differential_pressure, float& temp, float& velocity) override
{
unused(differential_pressure);
unused(temp);
unused(velocity);
throw std::runtime_error("Diff pressure sensor is not available");
}

Expand Down Expand Up @@ -202,6 +215,7 @@ class AirSimRosFlightBoard : public rosflight::Board {

virtual void system_reset(bool toBootloader) override
{
unused(toBootloader);
//no internal state to reset
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,18 +36,24 @@ class AirSimRosFlightCommLink : public rosflight::CommLink {

virtual void set_sys_id(int32_t sys_id)
{
unused(sys_id);
}

virtual void set_streaming_rate(uint16_t param_id, int32_t rate)
{
unused(param_id);
unused(rate);
}

virtual void notify_param_change(uint16_t param_id, int32_t value)
{
unused(param_id);
unused(value);
}

virtual void log_message(const char* message, uint8_t error_level)
{
unused(error_level);
messages_.push_back(std::string(message));
}

Expand Down
2 changes: 2 additions & 0 deletions AirLib/include/vehicles/MultiRotor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,8 @@ class MultiRotor : public PhysicsBody {

void updateSensors(MultiRotorParams& params, const Kinematics::State& state, const Environment& environment)
{
unused(state);
unused(environment);
params.getSensors().update();
}

Expand Down
2 changes: 2 additions & 0 deletions AirLib/include/vehicles/MultiRotorParams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,8 @@ class MultiRotorParams {
//below method is needed to support firmwares without state estimation. In future, we should probably remove this support.
virtual void initializePhysics(const Environment* environment, const Kinematics::State* kinematics)
{
unused(environment);
unused(kinematics);
//by default don't use it. If derived class needs this, it should override.
}

Expand Down
2 changes: 2 additions & 0 deletions AirLib/src/controllers/DroneControllerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ float DroneControllerBase::getAutoLookahead(float velocity, float adaptive_looka

float DroneControllerBase::getObsAvoidanceVelocity(float risk_dist, float max_obs_avoidance_vel)
{
unused(risk_dist);
return max_obs_avoidance_vel;
}

Expand Down Expand Up @@ -605,6 +606,7 @@ void DroneControllerBase::adjustYaw(float x, float y, DrivetrainType drivetrain,

void DroneControllerBase::moveToPathPosition(const Vector3r& dest, float velocity, DrivetrainType drivetrain, /* pass by value */ YawMode yaw_mode, float last_z)
{
unused(last_z);
//validate dest
if (dest.hasNaN())
throw std::invalid_argument(VectorMath::toString(dest,"dest vector cannot have NaN: "));
Expand Down
12 changes: 12 additions & 0 deletions AirLib/src/controllers/MavLinkDroneController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ class MavLinkLogViewerLog : public MavLinkLog
proxy_ = proxy;
}
void write(const mavlinkcom::MavLinkMessage& msg, uint64_t timestamp = 0) override {
unused(timestamp);
MavLinkMessage copy;
::memcpy(&copy, &msg, sizeof(MavLinkMessage));
proxy_->sendMessage(copy);
Expand Down Expand Up @@ -146,13 +147,15 @@ struct MavLinkDroneController::impl {
Utils::setValue(rotor_controls_, 0.0f);
//TODO: main_node_->setMessageInterval(...);
connection_->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg){
unused(connection);
processMavMessages(msg);
});

// listen to the other mavlink connection also
auto mavcon = mav_vehicle_->getConnection();
if (mavcon != connection_) {
mavcon->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg) {
unused(connection);
processMavMessages(msg);
});
}
Expand Down Expand Up @@ -217,6 +220,7 @@ struct MavLinkDroneController::impl {
}
else {
connection->subscribe([=](std::shared_ptr<MavLinkConnection> connection_val, const MavLinkMessage& msg){
unused(connection_val);
processQgcMessages(msg);
});
}
Expand Down Expand Up @@ -799,6 +803,8 @@ struct MavLinkDroneController::impl {

bool armDisarm(bool arm, CancelableBase& cancelable_action)
{
unused(arm);
unused(cancelable_action);
bool rc = false;
mav_vehicle_->armDisarm(arm).wait(10000, &rc);
return rc;
Expand Down Expand Up @@ -838,6 +844,8 @@ struct MavLinkDroneController::impl {

bool takeoff(float max_wait_seconds, CancelableBase& cancelable_action)
{
unused(cancelable_action);

bool rc = false;
auto vec = getPosition();
float z = vec.z() + getTakeoffZ();
Expand Down Expand Up @@ -871,6 +879,7 @@ struct MavLinkDroneController::impl {

bool land(CancelableBase& cancelable_action)
{
unused(cancelable_action);
// bugbug: really need a downward pointing distance to ground sensor to do this properly, for now
// we assume the ground is relatively flat an we are landing roughly at the home altitude.
updateState();
Expand Down Expand Up @@ -905,6 +914,7 @@ struct MavLinkDroneController::impl {

bool goHome(CancelableBase& cancelable_action)
{
unused(cancelable_action);
bool rc = false;
if (!mav_vehicle_->returnToHome().wait(10000, &rc)) {
throw VehicleMoveException("goHome - timeout waiting for response from drone");
Expand Down Expand Up @@ -948,11 +958,13 @@ struct MavLinkDroneController::impl {

void setRCData(const RCData& rcData)
{
unused(rcData);
//TODO: use RC data to control MavLink drone
}

bool validateRCData(const RCData& rc_data)
{
unused(rc_data);
return true;
}

Expand Down
3 changes: 3 additions & 0 deletions DroneShell/include/SimpleShell.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,7 @@ class SimpleShell {
private:
ShellCommand(){}
ShellCommand(ShellCommand& other){
unused(other);
}
};

Expand Down Expand Up @@ -204,6 +205,7 @@ class SimpleShell {

bool execute(const ShellCommandParameters& params)
{
unused(params);
return false;
}
};
Expand All @@ -218,6 +220,7 @@ class SimpleShell {

bool execute(const ShellCommandParameters& params)
{
unused(params);
return true;
}
};
Expand Down

0 comments on commit 6c4bf1a

Please sign in to comment.