Skip to content

Commit

Permalink
solve all compiler's warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
varhub committed Nov 24, 2015
1 parent 56cb2b9 commit 8f419b4
Show file tree
Hide file tree
Showing 6 changed files with 14 additions and 12 deletions.
2 changes: 1 addition & 1 deletion include/quadrotor/interfaces/cameraibase.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class CameraIBase: virtual public jderobot::Camera {

/// jderobot::Camera
jderobot::CameraDescriptionPtr getCameraDescription(const Ice::Current& c);
virtual Ice::Int setCameraDescription(const jderobot::CameraDescriptionPtr &description, const Ice::Current& c) { return 0; }
virtual Ice::Int setCameraDescription(const jderobot::CameraDescriptionPtr &/*description*/, const Ice::Current& /*c*/) { return 0; }


/// jderobot::StreamableCamera
Expand Down
2 changes: 1 addition & 1 deletion src/cameraproxy.cc
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ CameraProxy::_on_cam_update(){


cv::Mat
CameraProxy::_createImageWrapper(const gazebo::sensors::CameraSensorPtr cam, const int id) const{
CameraProxy::_createImageWrapper(const gazebo::sensors::CameraSensorPtr cam, const int /*id*/) const{
const unsigned char *data = cam->GetImageData();
uint32_t h = cam->GetImageHeight();
uint32_t w = cam->GetImageWidth();
Expand Down
8 changes: 4 additions & 4 deletions src/interfaces/cameraibase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ CameraIBase::~CameraIBase(){


ImageDescriptionPtr
CameraIBase::getImageDescription(const Ice::Current& c){
CameraIBase::getImageDescription(const Ice::Current& /*c*/){
ONDEBUG_VERBOSE(std::cout<<"CameraIBase::getImageDescription()"<<std::endl;)
lock_guard_t RAII_lock(mutex);
if (!imageDescription)
Expand All @@ -46,7 +46,7 @@ CameraIBase::getImageDescription(const Ice::Current& c){


ImageFormats
CameraIBase::getImageFormat(const Ice::Current& c) {
CameraIBase::getImageFormat(const Ice::Current& /*c*/) {
ONDEBUG_VERBOSE(std::cout<<"CameraIBase::getImageFormat()"<<std::endl;)
lock_guard_t RAII_lock(mutex);
if (imageFormats.empty())
Expand All @@ -67,7 +67,7 @@ CameraIBase::getImageData_async (const jderobot::AMD_ImageProvider_getImageDataP
}

void
CameraIBase::_getImageData_async (const jderobot::AMD_ImageProvider_getImageDataPtr& cb,const std::string& format, const Ice::Current& c){
CameraIBase::_getImageData_async (const jderobot::AMD_ImageProvider_getImageDataPtr& cb,const std::string& /*format*/, const Ice::Current& /*c*/){
//Non async response
if (!imageData)
throw DataNotExistException();
Expand All @@ -77,7 +77,7 @@ CameraIBase::_getImageData_async (const jderobot::AMD_ImageProvider_getImageData


CameraDescriptionPtr
CameraIBase::getCameraDescription(const Ice::Current& c){
CameraIBase::getCameraDescription(const Ice::Current& /*c*/){
ONDEBUG_VERBOSE(std::cout<<"CameraIBase::getCameraDescription()"<<std::endl;)
lock_guard_t RAII_lock(mutex);
if (!cameraDescription)
Expand Down
3 changes: 2 additions & 1 deletion src/interfaces/pose3di.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@ Pose3DI::getPose3DData ( const Ice::Current& ){
}

Ice::Int
Pose3DI::setPose3DData ( const jderobot::Pose3DDataPtr & data,
Pose3DI::setPose3DData ( const jderobot::Pose3DDataPtr & /*data*/,
const Ice::Current& ){
//ToDo: control
return 0;
}
9 changes: 5 additions & 4 deletions src/quadrotorcontrol.cc
Original file line number Diff line number Diff line change
Expand Up @@ -99,10 +99,9 @@ QuadrotorControl::setTargetVelocity(Twist twist){


void
QuadrotorControl::_update_state(const gazebo::common::UpdateInfo & _info){
Pose pose = base_link->GetWorldPose();
QuadrotorControl::_update_state(const gazebo::common::UpdateInfo & /*_info*/){
//Pose pose = base_link->GetWorldPose();
double altitude = sensors->altitude;
//std::cout<<"altotude "<<altitude<<std::endl;

switch(my_state){
case Unknown:
Expand All @@ -124,12 +123,13 @@ QuadrotorControl::_update_state(const gazebo::common::UpdateInfo & _info){
std::cout<<_log_prefix << "QuadrotorState::Flying" << std::endl;
}
break;
default: break;
}
}


void
QuadrotorControl::_control_loop_novel(const gazebo::common::UpdateInfo & _info){
QuadrotorControl::_control_loop_novel(const gazebo::common::UpdateInfo & /*_info*/){
//// Forces and velocities are handled bt a physics engine
/// This means that we must apply a counter-gravity force
/// each cicle to model "fly" state.
Expand Down Expand Up @@ -158,6 +158,7 @@ QuadrotorControl::_control_loop_novel(const gazebo::common::UpdateInfo & _info){
vel_model = vel_model+up_down_vel;// pose.rot.RotateVector(vel_world+up_down_vel);
base_link->SetLinearVel(vel_model);
break;
default: break;
}

if (my_state != QuadrotorState::Landed){
Expand Down
2 changes: 1 addition & 1 deletion src/quadrotorplugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ QuadrotorPlugin::Init(){


void
QuadrotorPlugin::OnUpdate(const UpdateInfo & _info){
QuadrotorPlugin::OnUpdate(const UpdateInfo & ONDEBUG_VERBOSE(_info)){
ONDEBUG_VERBOSE(std::cout << _log_prefix << "QuadrotorPlugin::OnUpdate()\n\t" << _info.simTime << std::endl;)
}

Expand Down

0 comments on commit 8f419b4

Please sign in to comment.