// ROS node that publishes the localization data from sensor fusion of the crazyflie, using uwb for coordinates
// Copyright (C) 2017 Michael Rogenmoser, Tiago Salzmann, Yvan Bosshard
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with this program. If not, see .
#define DEG2RAD 0.01745329251
#include
#include
#include
#include
#include
#include "d_fall_pps/CMQuery.h"
#include "d_fall_pps/Anchors.h"
#include "d_fall_pps/CrazyflieData.h"
#include "d_fall_pps/CrazyflieContext.h"
#include "IndoorNewton.h"
#include "UWBDataPublisher.h"
using namespace d_fall_pps;
// Kalmanfilter Variables
#define KALMAN_M_VARIANCE 0.01 // was 1
#define KALMAN_P_VARIANCE 0.0001
#define DISTANCE_ERROR_TRESHOLD 0.9
// the clientID defines namespace and identifier in the CentralManagerService
int clientID;
// UWB Anchor error handling
const unsigned long print_timeout = 1000; // in ms
bool printBadReading[UWB_NUM_ANCHORS] = {false};
bool printError[UWB_NUM_ANCHORS] = {false};
std::chrono::high_resolution_clock::time_point lastPrint;
CrazyflieContext context;
rosbag::Bag bag;
ros::ServiceClient centralManager;
ros::ServiceClient uwbManager;
ros::Publisher UWBDataPublisher;
ros::Publisher UWBLogPublisher;
double rollPitchYaw[3];
UWBAnchorArray anchors;
double anchorPositions[3*UWB_NUM_ANCHORS];
double lastDistances[UWB_NUM_ANCHORS] = {0};
static KalmanState xState;
static KalmanState yState;
static KalmanState zState;
KalmanState kalmanDist[UWB_NUM_ANCHORS];
std::chrono::high_resolution_clock::time_point lastRPY;
unsigned long whatever = 0;
unsigned int whatever_counter = 0;
std::chrono::high_resolution_clock::time_point lastDist;
unsigned long whatever2 = 0;
unsigned int whatever_counter2 = 0;
int main(int argc, char* argv[])
{
ros::init(argc, argv, "UWBDataPublisher");
ros::NodeHandle nodeHandle("~");
ros::NodeHandle namespaceNodeHandle = ros::NodeHandle();
lastPrint = std::chrono::high_resolution_clock::now();
if(!loadParameters(nodeHandle))
return -1;
centralManager = nodeHandle.serviceClient("/CentralManagerService/Query", false);
loadCrazyflieContext();
ros::Subscriber dbChangedSubscriber = nodeHandle.subscribe("/my_GUI/DBChanged", 1, dbChangedCallback);
uwbManager = nodeHandle.serviceClient("/UWBManagerService/UWBData", false);
ros::Subscriber enableUWBSubscriber = nodeHandle.subscribe("/my_GUI/enableUWB", 1, uwbChangedCallback);
// Subscribe to the anchor positions and all relevant Data from crazyradio
ros::Subscriber cfRPYSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/RPY",10,cfRPYCallback);
ros::Subscriber uwbLocationSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/AnchorDistances", 10, cfDistancesCallback);
UWBDataPublisher = nodeHandle.advertise("UWBData", 10);
UWBLogPublisher = nodeHandle.advertise("Distances", 1);
std::string package_path;
package_path = ros::package::getPath("d_fall_pps") + "/";
std::string record_file = package_path + "log/UWBDataPublisherLog.bag";
bag.open(record_file, rosbag::bagmode::Write);
initKalmanStates();
loadUWBSettings();
ROS_INFO_STREAM("[UWBDataPublisher] started!");
ros::spin();
bag.close();
return 0;
}
void d_fall_pps::dbChangedCallback(const std_msgs::Int32& msg)
{
d_fall_pps::loadCrazyflieContext();
}
void d_fall_pps::uwbChangedCallback(const std_msgs::Int32& msg)
{
d_fall_pps::loadUWBSettings();
}
void d_fall_pps::loadUWBSettings()
{
Anchors a;
if(uwbManager.call(a))
{
anchors = a.response.anchorArray;
}
else
{
ROS_ERROR("[UWBDataPublisher] Could not update UWB Settings!");
}
for(int i = 0; i < UWB_NUM_ANCHORS; ++i)
{
anchorPositions[3*i] = anchors.data[i].x;
anchorPositions[3*i + 1] = anchors.data[i].y;
anchorPositions[3*i + 2] = anchors.data[i].z;
}
}
//Callback function to handle roll pitch yaw information from CF
void d_fall_pps::cfRPYCallback(const std_msgs::Float32MultiArray &arrRPY)
{
// Just to check how often these get published
/*std::chrono::high_resolution_clock::time_point thisRPY = std::chrono::high_resolution_clock::now();
whatever += std::chrono::duration_cast(thisRPY - lastRPY).count();
++whatever_counter;
lastRPY = thisRPY;
if(whatever_counter > 100)
{
double frq = 1000.0 * whatever_counter / whatever;
ROS_WARN("RPY at %lf Hz", frq);
whatever_counter = 0;
whatever = 0;
}*/
rollPitchYaw[0] = arrRPY.data[0] * DEG2RAD;
rollPitchYaw[1] = arrRPY.data[1] * DEG2RAD;
rollPitchYaw[2] = arrRPY.data[2] * DEG2RAD;
}
// Callback functions to handle times information from CF
void d_fall_pps::cfDistancesCallback(const std_msgs::UInt32MultiArray &distances)
{
// Just to check how often these get published
/*std::chrono::high_resolution_clock::time_point thisDist = std::chrono::high_resolution_clock::now();
whatever2 += std::chrono::duration_cast(thisDist - lastDist).count();
++whatever_counter2;
lastDist = thisDist;
if(whatever_counter2 > 100)
{
double frq = 1000.0 * whatever_counter2 / whatever2;
ROS_WARN("Dist at %lf Hz", frq);
whatever_counter2 = 0;
whatever2 = 0;
}*/
CrazyflieData data;
double arrXYZ[3] = {0};
calculateXYZ(distances, arrXYZ);
data.crazyflieName = context.crazyflieName;
data.x = arrXYZ[0];
data.y = arrXYZ[1];
data.z = arrXYZ[2];
data.roll = rollPitchYaw[0];
data.pitch = -1*rollPitchYaw[1];
data.yaw = rollPitchYaw[2];
data.occluded = false;
data.acquiringTime = 0; //???
UWBDataPublisher.publish(data);
}
//calculates position from anchor locations and distances -> forces algorithm?
void d_fall_pps::calculateXYZ(const std_msgs::UInt32MultiArray& distances, double(&xyz)[3])
{
double dist[UWB_NUM_ANCHORS];
double result[3];
std::chrono::high_resolution_clock::time_point thisPrint = std::chrono::high_resolution_clock::now();
unsigned long printdiff = std::chrono::duration_cast(thisPrint - lastPrint).count();
for(unsigned int i = 0; i < UWB_NUM_ANCHORS; i++)
{
if(abs(lastDistances[i] - distances.data[i] / 100.0) > DISTANCE_ERROR_TRESHOLD)
printBadReading[i] = true;
dist[i] = distances.data[i] / 100.0; //in dm
lastDistances[i] = dist[i];
if(distances.data[i] == 0)
printError[i] = true;
}
if(printdiff > print_timeout)
{
for(unsigned int i = 0; i < UWB_NUM_ANCHORS; ++i)
{
if(printError[i])
ROS_ERROR("Error with Anchor %i", i+1);
printError[i] = false;
if(printBadReading[i])
ROS_WARN("Bad reading from Anchor %i", i+1);
printBadReading[i] = false;
}
lastPrint = thisPrint;
}
//filterDistances(dist);
/*for(int i = 0; i < UWB_NUM_ANCHORS; ++i)
{
ROS_WARN("Anchor %i: (%f, %f, %f)", i, anchorPositions[3*i], anchorPositions[3*i+1], anchorPositions[3*i+2]);
}*/
IndoorNewton(anchorPositions, dist, result, 50);
//ROS_INFO_STREAM(result[0]);
updateKalmanState(xState, result[0] / 10.0);
updateKalmanState(yState, result[1] / 10.0);
updateKalmanState(zState, result[2] / 10.0);
// Use this for Kalmanfiltered position
xyz[0] = xState.x;
xyz[1] = yState.x;
xyz[2] = zState.x;
//ROS_WARN("Kalman: (%f, %f, %f)", xState.x, yState.x, zState.x);
// Use this for unfiltered position
// xyz[0] = result[0] / 10.0;
// xyz[1] = result[1] / 10.0;
//xyz[2] = result[2] / 10.0;
publishLog(distances, dist);
}
void d_fall_pps::publishLog(const std_msgs::UInt32MultiArray& distances, const double* dist)
{
std_msgs::Float32MultiArray msg;
msg.data = {};
for(int i = 0; i < UWB_NUM_ANCHORS; ++i)
{
msg.data.push_back(distances.data[i] / 100.0);
}
for(int i = 0; i < UWB_NUM_ANCHORS; ++i)
{
msg.data.push_back(dist[i]);
}
/* for(int i = 0; i < 2 * UWB_NUM_ANCHORS; ++i)
ROS_WARN("%i, %f", i, msg.data[i]);*/
UWBLogPublisher.publish(msg);
}
void d_fall_pps::filterDistances(double* distances)
{
for (unsigned int i = 0; i < UWB_NUM_ANCHORS; i++)
{
updateKalmanState(kalmanDist[i], distances[i]);
// if(distances[i] != 0)
// updateKalmanState(kalmanDist[i], distances[i]);
distances[i] = kalmanDist[i].x;
}
}
void d_fall_pps::initKalmanStates()
{
// Init x state
// TODO Update
xState.x = 0;
xState.q = KALMAN_P_VARIANCE;
xState.r = KALMAN_M_VARIANCE;
xState.p = 0;
// Init y state
// TODO Update
yState.x = 0;
yState.q = KALMAN_P_VARIANCE;
yState.r = KALMAN_M_VARIANCE;
yState.p = 0;
// Init z state
// TODO Update
zState.x = 0;
zState.q = 5e-6; //KALMAN_P_VARIANCE;
zState.r = 5e-4; //KALMAN_M_VARIANCE;
zState.p = 0;
for(unsigned int i = 0; i < UWB_NUM_ANCHORS; i++)
{
kalmanDist[i].x = 0;
kalmanDist[i].q = 8;
kalmanDist[i].r = 500;
kalmanDist[i].p = 0;
}
}
void d_fall_pps::updateKalmanState(KalmanState& state, double measurment)
{
state.p += state.q;
state.k = state.p / (state.p + state.r);
state.x += state.k * (measurment - state.x);
state.p *= (1 - state.k);
}
// Loads the current context of the client
void d_fall_pps::loadCrazyflieContext()
{
CMQuery contextCall;
contextCall.request.studentID = clientID;
centralManager.waitForExistence(ros::Duration(-1));
if(centralManager.call(contextCall))
{
context = contextCall.response.crazyflieContext;
ROS_INFO_STREAM("[UWBDataPublisher] context updated");
}
}
// Loads the parameters of the node handle
bool d_fall_pps::loadParameters(ros::NodeHandle &nodeHandle)
{
if(!nodeHandle.getParam("clientID", clientID))
{
ROS_ERROR("Failed to get clientID!");
return false;
}
return true;
}
// calculatse distances from passed microseconds
float d_fall_pps::tiagosAwesomeFormula(uint32_t ticks)
{
return ticks * SPEED_OF_LIGHT / LOCO_DECK_FRQ;
//return (time * 75.0 * (1.0 / (128.0 * 499.2)));
}