|
@@ -40,7 +40,8 @@ using namespace std;
|
|
|
|
|
|
|
|
|
|
|
|
-pilot_autoware_bridge::pilot_autoware_bridge() : Node("testpose_core")
|
|
|
+
|
|
|
+pilot_autoware_bridge::pilot_autoware_bridge() : Node("pilot_autoware_bridge")
|
|
|
{
|
|
|
QString str;
|
|
|
using std::placeholders::_1;
|
|
@@ -65,6 +66,9 @@ pub_velocity_ = create_publisher<VelocityReport>("/vehicle/status/velocity_statu
|
|
|
pub_steer_ = create_publisher<SteeringReport>("/vehicle/status/steering_status", durable_qos);
|
|
|
pub_acc_ = create_publisher<AccelWithCovarianceStamped>("/localization/acceleration", durable_qos);
|
|
|
|
|
|
+sub_cmd_ = create_subscription<AckermannControlCommand>(
|
|
|
+ "/vehicle/command/manual_control_cmd", 1, [this](const AckermannControlCommand::SharedPtr msg) { mpcmd_ptr = msg; std::cout<<"new cmd. "<<std::endl;});
|
|
|
+
|
|
|
mptimer= create_wall_timer(100ms,std::bind(&pilot_autoware_bridge::callbackTimer, this));
|
|
|
|
|
|
ModuleFun fungpsimu =std::bind(&pilot_autoware_bridge::UpdateGPSIMU,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
|
|
@@ -360,7 +364,7 @@ void pilot_autoware_bridge::UpdateGPSIMU(const char * strdata,const unsigned int
|
|
|
}
|
|
|
|
|
|
double flat = xgpsimu.lat();
|
|
|
- double flon = xgpsimu.lon();
|
|
|
+ double flon = xgpsimu.lon();
|
|
|
|
|
|
double pitch,roll,yaw;
|
|
|
pitch = 0;
|