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

Add an initial yaw command #59

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
4 changes: 2 additions & 2 deletions src/stateestimation/DroneKalmanFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,13 +363,13 @@ void DroneKalmanFilter::observeIMU_RPY(const ardrone_autonomy::Navdata* nav)

if(!baselinesYValid) // only for initialization.
{
baselineY_IMU = nav->rotZ;
baselineY_IMU = nav->rotZ - node->initialYaw;
baselineY_Filter = yaw.state[0];
baselinesYValid = true;
timestampYawBaselineFrom = getMS(nav->header.stamp);
}

double imuYawDiff = (nav->rotZ - baselineY_IMU );
double imuYawDiff = (nav->rotZ - node->initialYaw - baselineY_IMU );
double observedYaw = baselineY_Filter + imuYawDiff;

yaw.state[0] = angleFromTo(yaw.state[0],-180,180);
Expand Down
12 changes: 12 additions & 0 deletions src/stateestimation/EstimationNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ EstimationNode::EstimationNode()
arDroneVersion = 0;
//memset(&lastNavdataReceived,0,sizeof(ardrone_autonomy::Navdata));

initialYaw = 0;

}

Expand Down Expand Up @@ -239,8 +240,19 @@ void EstimationNode::comCb(const std_msgs::StringConstPtr str)
this->toogleLogging();
}

// hack to handle the setinitialstate command

// only handle commands with prefix c
if(str->data.length() > 2 && str->data.substr(0,2) == "c ")
{

float parameter;
// setInitialYaw
if(sscanf(str->data.c_str(),"c setInitialYaw %f",&parameter) == 1)
{
initialYaw = parameter;
}
}


int a, b;
Expand Down
4 changes: 2 additions & 2 deletions src/stateestimation/EstimationNode.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
*/
#ifndef __ESTIMATIONNODE_H
#define __ESTIMATIONNODE_H


#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
Expand Down Expand Up @@ -134,7 +134,7 @@ struct EstimationNode
void toogleLogging(); // switches logging on or off.
std::string calibFile;
int arDroneVersion;

float initialYaw;

};
#endif /* __ESTIMATIONNODE_H */