Skip to content

Commit

Permalink
fix some CLang compile warnings.
Browse files Browse the repository at this point in the history
  • Loading branch information
lovettchris committed Mar 24, 2017
1 parent ad107c0 commit 2582cd4
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 7 deletions.
4 changes: 2 additions & 2 deletions MavLinkCom/MavLinkTest/Commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -440,8 +440,8 @@ void PlayLogCommand::Execute(std::shared_ptr<MavLinkVehicle> com)
std::copy(quaternion_, quaternion_ + 1, mocap.q);
com->writeMessage(mocap);
break;
}
default:
}
default:
break;
}
}
Expand Down
2 changes: 1 addition & 1 deletion MavLinkCom/MavLinkTest/Commands.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class Command
static Command* create(const std::vector<std::string>& args);
static std::vector<Command*> const * getAllCommand();
static void setAllCommand(std::vector<Command*> const * all_commands);
static constexpr char* kCommandLogPrefix = "cmd:";
static constexpr const char* kCommandLogPrefix = "cmd:";
protected:
std::shared_ptr<MavLinkVehicle> vehicle;
private:
Expand Down
6 changes: 2 additions & 4 deletions MavLinkCom/src/impl/MavLinkNodeImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,8 +264,7 @@ std::vector<MavLinkParameter> MavLinkNodeImpl::getParamList()
bool done = false;
Semaphore paramReceived;
bool waiting = false;
int paramCount = 0;
int paramIndex = 0;
size_t paramCount = 0;

auto con = ensureConnection();
int subscription = con->subscribe([&](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& message) {
Expand All @@ -282,7 +281,6 @@ std::vector<MavLinkParameter> MavLinkNodeImpl::getParamList()
p.name = buf;
p.value = param.param_value;
result.push_back(p);
paramIndex = param.param_index;
paramCount = param.param_count;
if (param.param_index == param.param_count - 1)
{
Expand Down Expand Up @@ -321,7 +319,7 @@ std::vector<MavLinkParameter> MavLinkNodeImpl::getParamList()
for (auto iter = result.begin(), end = result.end(); iter != end; iter++)
{
MavLinkParameter p = *iter;
if (p.index == i) {
if (static_cast<size_t>(p.index) == i) {
found = true;
break;
}
Expand Down

0 comments on commit 2582cd4

Please sign in to comment.