|
@@ -39,6 +39,8 @@
|
|
//#include "modulecomm.h"
|
|
//#include "modulecomm.h"
|
|
using namespace std;
|
|
using namespace std;
|
|
|
|
|
|
|
|
+static double gfchassis_acc = 0;
|
|
|
|
+
|
|
|
|
|
|
pilot_autoware_bridge::pilot_autoware_bridge() : Node("pilot_autoware_bridge")
|
|
pilot_autoware_bridge::pilot_autoware_bridge() : Node("pilot_autoware_bridge")
|
|
{
|
|
{
|
|
@@ -273,7 +275,7 @@ void pilot_autoware_bridge::callbackTimerGPS()
|
|
double flat = xgpsimu.lat();
|
|
double flat = xgpsimu.lat();
|
|
double flon = xgpsimu.lon();
|
|
double flon = xgpsimu.lon();
|
|
|
|
|
|
- mfacc = xgpsimu.acce_x();
|
|
|
|
|
|
+ mfacc = gfchassis_acc;//xgpsimu.acce_x();
|
|
|
|
|
|
double pitch,roll,yaw;
|
|
double pitch,roll,yaw;
|
|
pitch = 0;
|
|
pitch = 0;
|
|
@@ -331,6 +333,7 @@ void pilot_autoware_bridge::callbackTimerGPS()
|
|
int nochassiscount = 0;
|
|
int nochassiscount = 0;
|
|
|
|
|
|
nread = mpsharechassis->read(strdata,10000);
|
|
nread = mpsharechassis->read(strdata,10000);
|
|
|
|
+
|
|
|
|
|
|
if(nread < 1)
|
|
if(nread < 1)
|
|
{
|
|
{
|
|
@@ -343,6 +346,8 @@ void pilot_autoware_bridge::callbackTimerGPS()
|
|
}
|
|
}
|
|
else
|
|
else
|
|
{
|
|
{
|
|
|
|
+ static int64_t nchassislast = 0;
|
|
|
|
+ static double fchassis_veh_last = 0;
|
|
iv::chassis xchassis;
|
|
iv::chassis xchassis;
|
|
// static int ncount = 0;
|
|
// static int ncount = 0;
|
|
if(!xchassis.ParseFromArray(strdata,nread))
|
|
if(!xchassis.ParseFromArray(strdata,nread))
|
|
@@ -352,6 +357,21 @@ void pilot_autoware_bridge::callbackTimerGPS()
|
|
else
|
|
else
|
|
{
|
|
{
|
|
steear_now = (xchassis.angle_feedback() *M_PI/180.0)/15.0;
|
|
steear_now = (xchassis.angle_feedback() *M_PI/180.0)/15.0;
|
|
|
|
+ double fchassis_veh_now = xchassis.vel()/3.6;
|
|
|
|
+ int64_t nchassis_now = xchassis.time();
|
|
|
|
+ int64_t ndiff = nchassis_now - nchassislast;
|
|
|
|
+ double fdiff = ndiff/1e9;
|
|
|
|
+ if(fdiff > 0)
|
|
|
|
+ {
|
|
|
|
+ gfchassis_acc = (fchassis_veh_now - fchassis_veh_last) /fdiff;
|
|
|
|
+ std::cout<<" acc: "<<gfchassis_acc<<std::endl;
|
|
|
|
+ }
|
|
|
|
+ else
|
|
|
|
+ {
|
|
|
|
+ gfchassis_acc = 0;
|
|
|
|
+ }
|
|
|
|
+ nchassislast = nchassis_now;
|
|
|
|
+ fchassis_veh_last = fchassis_veh_now;
|
|
nochassiscount = 0;
|
|
nochassiscount = 0;
|
|
// std::cout<<" steer : "<<steear_now<<std::endl;
|
|
// std::cout<<" steer : "<<steear_now<<std::endl;
|
|
}
|
|
}
|
|
@@ -531,7 +551,7 @@ void pilot_autoware_bridge::UpdateGPSIMU(const char * strdata,const unsigned int
|
|
double flat = xgpsimu.lat();
|
|
double flat = xgpsimu.lat();
|
|
double flon = xgpsimu.lon();
|
|
double flon = xgpsimu.lon();
|
|
|
|
|
|
- mfacc = xgpsimu.acce_x();
|
|
|
|
|
|
+ mfacc = gfchassis_acc; //xgpsimu.acce_x();
|
|
|
|
|
|
double pitch,roll,yaw;
|
|
double pitch,roll,yaw;
|
|
pitch = 0;
|
|
pitch = 0;
|