Skip to content

Commit

Permalink
Fix remote HIL mode and some compiler warnings.
Browse files Browse the repository at this point in the history
  • Loading branch information
clovett committed Feb 20, 2017
1 parent 3bb79b5 commit 3a2f045
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 13 deletions.
7 changes: 6 additions & 1 deletion AirLib/src/control/MavLinkHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -279,7 +279,12 @@ struct MavLinkHelper::impl {
void createHILUdpConnection(const std::string& ip, int port)
{
close();
connection_ = MavLinkConnection::connectLocalUdp("hil", ip, port);
if (ip == LocalHostIp) {
connection_ = MavLinkConnection::connectLocalUdp("hil", ip, port);
}
else {
connection_ = MavLinkConnection::connectRemoteUdp("hil", LocalHostIp, ip, port);
}
main_node_ = std::make_shared<MavLinkNode>(SimSysID, SimCompID);
main_node_->connect(connection_);
}
Expand Down
20 changes: 10 additions & 10 deletions MavLinkCom/MavLinkTest/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -449,15 +449,15 @@ void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
double bSq = b * b;
double cSq = c * c;
double dSq = d * d;
dcm[0][0] = aSq + bSq - cSq - dSq;
dcm[0][1] = 2 * (b * c - a * d);
dcm[0][2] = 2 * (a * c + b * d);
dcm[1][0] = 2 * (b * c + a * d);
dcm[1][1] = aSq - bSq + cSq - dSq;
dcm[1][2] = 2 * (c * d - a * b);
dcm[2][0] = 2 * (b * d - a * c);
dcm[2][1] = 2 * (a * b + c * d);
dcm[2][2] = aSq - bSq - cSq + dSq;
dcm[0][0] = static_cast<float>(aSq + bSq - cSq - dSq);
dcm[0][1] = static_cast<float>(2 * (b * c - a * d));
dcm[0][2] = static_cast<float>(2 * (a * c + b * d));
dcm[1][0] = static_cast<float>(2 * (b * c + a * d));
dcm[1][1] = static_cast<float>(aSq - bSq + cSq - dSq);
dcm[1][2] = static_cast<float>(2 * (c * d - a * b));
dcm[2][0] = static_cast<float>(2 * (b * d - a * c));
dcm[2][1] = static_cast<float>(2 * (a * b + c * d));
dcm[2][2] = static_cast<float>(aSq - bSq - cSq + dSq);
}
void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
{
Expand Down Expand Up @@ -956,7 +956,7 @@ int console() {
sendImage->setLogViewer(logViewer);
}

checkPulse(mavLinkVehicle);
//checkPulse(mavLinkVehicle);

int retries = 0;
while (retries++ < 5) {
Expand Down
2 changes: 1 addition & 1 deletion MavLinkCom/src/impl/MavLinkConnectionImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -298,7 +298,7 @@ void MavLinkConnectionImpl::readPackets()
std::lock_guard<std::mutex> guard(msg_queue_mutex_);
MavLinkMessage& message = reinterpret_cast<MavLinkMessage&>(msg);
msg_queue_.push(message);
long size = msg_queue_.size();
size_t size = msg_queue_.size();
if (size > max_queue_length_) {
max_queue_length_ = size;
}
Expand Down
2 changes: 1 addition & 1 deletion MavLinkCom/src/impl/MavLinkConnectionImpl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ namespace mavlinkcom_impl {
std::mutex msg_queue_mutex_;
MavLinkSemaphore msg_available_;
bool waiting_for_msg_ = false;
long max_queue_length_ = 0;
size_t max_queue_length_ = 0;
long mavlink_errors_ = 0;
};
}
Expand Down

0 comments on commit 3a2f045

Please sign in to comment.