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

Reduce compilation warnings #64

Open
wants to merge 1 commit into
base: indigo-devel
Choose a base branch
from
Open
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
2 changes: 1 addition & 1 deletion src/UINode/PingThread.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void PingThread::stopSystem()
double parsePingResult(std::string s)
{
// 20008 bytes from localhost (127.0.0.1): icmp_req=1 ttl=64 time=0.075 ms
int pos = s.find("time=");
size_t pos = s.find("time=");
int found = 0;
float ms;
if(pos != std::string::npos)
Expand Down
2 changes: 1 addition & 1 deletion src/UINode/tum_ardrone_gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -401,7 +401,7 @@ ControlCommand tum_ardrone_gui::calcKBControl()
{
// clear keys that have not been refreshed for 1s, it is set to "not pressed"
for(int i=0;i<8;i++)
isPressed[i] = isPressed[i] && ((lastRepeat[i] + 1000) > getMS());
isPressed[i] = isPressed[i] && ((lastRepeat[i] + 1000) > (unsigned int)getMS());

ControlCommand c;

Expand Down
4 changes: 2 additions & 2 deletions src/autopilot/ControlNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,12 +167,12 @@ void ControlNode::popNextCommand(const tum_ardrone::filter_stateConstPtr statePt
float parameters[10];

// replace macros
if((p = command.find("$POSE$")) != std::string::npos)
if((size_t)(p = command.find("$POSE$")) != std::string::npos)
{
snprintf(buf,100, "%.3f %.3f %.3f %.3f",statePtr->x,statePtr->y,statePtr->z,statePtr->yaw);
command.replace(p,6,buf);
}
if((p = command.find("$REFERENCE$")) != std::string::npos)
if((size_t)(p = command.find("$REFERENCE$")) != std::string::npos)
{
snprintf(buf,100, "%.3f %.3f %.3f %.3f",parameter_referenceZero.pos[0],parameter_referenceZero.pos[1],parameter_referenceZero.pos[2],parameter_referenceZero.yaw);
command.replace(p,11,buf);
Expand Down
4 changes: 2 additions & 2 deletions src/autopilot/DroneController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ ControlCommand DroneController::update(tum_ardrone::filter_stateConstPtr state)
TooN::Vector<3> pose = TooN::makeVector(state->x, state->y, state->z);
double yaw = state->yaw;
TooN::Vector<4> speeds = TooN::makeVector(state->dx, state->dy, state->dz, state->dyaw);
ptamIsGood = state->ptamState == state->PTAM_BEST || state->ptamState == state->PTAM_GOOD || state->ptamState == state->PTAM_TOOKKF;
ptamIsGood = state->ptamState == (unsigned int)state->PTAM_BEST || state->ptamState == (unsigned int)state->PTAM_GOOD || state->ptamState == (unsigned int)state->PTAM_TOOKKF;
scaleAccuracy = state->scaleAccuracy;

// calculate (new) errors.
Expand Down Expand Up @@ -96,7 +96,7 @@ void DroneController::setTarget(DronePosition newTarget)

char buf[200];
snprintf(buf,200,"New Target: xyz = %.3f, %.3f, %.3f, yaw=%.3f", target.pos[0],target.pos[1],target.pos[2],target.yaw);
ROS_INFO(buf);
ROS_INFO("%s", buf);

if(node != NULL)
node->publishCommand(std::string("u l ") + buf);
Expand Down
4 changes: 2 additions & 2 deletions src/autopilot/KI/KIAutoInit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ bool KIAutoInit::update(const tum_ardrone::filter_stateConstPtr statePtr)
}
else // time is up, take second KF
{
if(statePtr->ptamState == statePtr->PTAM_INITIALIZING) // TODO: ptam status enum, this should be PTAM_INITIALIZING
if(statePtr->ptamState == (unsigned int)statePtr->PTAM_INITIALIZING) // TODO: ptam status enum, this should be PTAM_INITIALIZING
{
node->publishCommand("p space");
stageStarted = getMS();
Expand All @@ -155,7 +155,7 @@ bool KIAutoInit::update(const tum_ardrone::filter_stateConstPtr statePtr)
case WAIT_FOR_SECOND:

// am i done?
if(statePtr->ptamState == statePtr->PTAM_BEST || statePtr->ptamState == statePtr->PTAM_GOOD || statePtr->ptamState == statePtr->PTAM_TOOKKF) // TODO: PTAM_GOOD or PTAM_BEST or PTAM_TOOKKF
if(statePtr->ptamState == (unsigned int)statePtr->PTAM_BEST || statePtr->ptamState == (unsigned int)statePtr->PTAM_GOOD || statePtr->ptamState == (unsigned int)statePtr->PTAM_TOOKKF) // TODO: PTAM_GOOD or PTAM_BEST or PTAM_TOOKKF
{
controller->setTarget(DronePosition(
TooN::makeVector(statePtr->x,statePtr->y,statePtr->z),statePtr->yaw));
Expand Down
4 changes: 1 addition & 3 deletions src/stateestimation/EstimationNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -531,7 +531,7 @@ void EstimationNode::reSendInfo()
// parse PTAM message
std::string ptamMsg = ptamWrapper->lastPTAMMessage;
int kf, kp, kps[4], kpf[4];
int pos = ptamMsg.find("Found: ");
size_t pos = ptamMsg.find("Found: ");
int found = 0;
if(pos != std::string::npos)
found = sscanf(ptamMsg.substr(pos).c_str(),"Found: %d/%d %d/%d %d/%d %d/%d Map: %dP, %dKF",
Expand All @@ -543,8 +543,6 @@ void EstimationNode::reSendInfo()
else
snprintf(bufp,200,"Map: -");

lastNavdataReceived.batteryPercent;

std::string status = "";
switch( lastNavdataReceived.state)
{
Expand Down
1 change: 0 additions & 1 deletion src/stateestimation/PTAM/MiniPatch.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ bool MiniPatch::FindPatch(CVD::ImageRef &irPos,
vector<ImageRef> &vCorners,
std::vector<int> *pvRowLUT)
{
ImageRef irCenter = irPos;
ImageRef irBest;
int nBestSSD = mnMaxSSD + 1;
ImageRef irBBoxTL = irPos - ImageRef(nRange, nRange);
Expand Down
14 changes: 7 additions & 7 deletions src/stateestimation/PTAMWrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ void PTAMWrapper::run()


snprintf(charBuf,200,"Video resolution: %d x %d",frameWidth,frameHeight);
ROS_INFO(charBuf);
ROS_INFO("%s", charBuf);
node->publishCommand(std::string("u l ")+charBuf);

// create window
Expand Down Expand Up @@ -498,13 +498,13 @@ void PTAMWrapper::HandleFrame()
//filter->useScalingFixpoint = true;

snprintf(charBuf,500,"locking scale fixpoint to %.3f %.3f %.3f",PTAMResultTransformed[0], PTAMResultTransformed[1], PTAMResultTransformed[2]);
ROS_INFO(charBuf);
ROS_INFO("%s", charBuf);
node->publishCommand(std::string("u l ")+charBuf);
}


// ----------------------------- Take KF? -----------------------------------
if(!mapLocked && isVeryGood && (forceKF || mpMap->vpKeyFrames.size() < maxKF || maxKF <= 1))
if(!mapLocked && isVeryGood && (forceKF || (int)(mpMap->vpKeyFrames.size()) < maxKF || maxKF <= 1))
{
mpTracker->TakeKF(forceKF);
forceKF = false;
Expand Down Expand Up @@ -572,7 +572,7 @@ void PTAMWrapper::HandleFrame()
fle->flush();
fle->close();

printf("FLUSHED %d KEYPOINTS to file pointcloud.txt\n\n",mapPointsTransformed.size());
printf("FLUSHED %lu KEYPOINTS to file pointcloud.txt\n\n",mapPointsTransformed.size());

flushMapKeypoints = false;
}
Expand Down Expand Up @@ -812,12 +812,12 @@ TooN::Vector<3> PTAMWrapper::evalNavQue(unsigned int from, unsigned int to, bool
)
{
int frontStamp = getMS(cur->header.stamp);
if(frontStamp < from) // packages before: delete
if(frontStamp < (int)from) // packages before: delete
{
//navInfoQueue.pop_front();
skipped++;
}
else if(frontStamp >= from && frontStamp <= to)
else if(frontStamp >= (int)from && frontStamp <= (int)to)
{
if(firstAdded == 0)
{
Expand Down Expand Up @@ -922,7 +922,7 @@ void PTAMWrapper::newImage(sensor_msgs::ImageConstPtr img)

// copy to mimFrame.
// TODO: make this threadsafe (save pointer only and copy in HandleFrame)
if(mimFrameBW.size().x != img->width || mimFrameBW.size().y != img->height)
if(mimFrameBW.size().x != (int)(img->width) || mimFrameBW.size().y != (int)(img->height))
mimFrameBW.resize(CVD::ImageRef(img->width, img->height));

memcpy(mimFrameBW.data(),cv_ptr->image.data,img->width * img->height);
Expand Down