|
@@ -22,6 +22,7 @@
|
|
|
|
|
|
#include "rawpic.pb.h"
|
|
|
#include "odom.pb.h"
|
|
|
+#include "decition.pb.h"
|
|
|
|
|
|
static std::string _point_topic = "/points_raw";
|
|
|
static std::string _point_msgname = "lidarpc_ros";
|
|
@@ -197,6 +198,54 @@ void testvh()
|
|
|
}
|
|
|
}
|
|
|
|
|
|
+void UpdateDecition(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
|
|
|
+{
|
|
|
+
|
|
|
+ static int x = 0;
|
|
|
+ iv::brain::decition xdecition;
|
|
|
+ std::cout<<" nSize : "<<nSize<<std::endl;
|
|
|
+ if(!xdecition.ParseFromArray(strdata,nSize))
|
|
|
+ {
|
|
|
+ std::cout<<" UpdateDecition Parse error."<<std::endl;
|
|
|
+ return;
|
|
|
+ }
|
|
|
+ //ServiceCarStatus.mfAcc = xdecition.accelerator(); //
|
|
|
+ autoware_msgs::VehicleCmd xcmd;
|
|
|
+
|
|
|
+ xcmd.header.seq = x;
|
|
|
+
|
|
|
+
|
|
|
+ std::cout<<" acc : "<<xdecition.accelerator()<<std::endl;
|
|
|
+ //xcmd.ctrl_cmd.linear_acceleration =0.1;
|
|
|
+ xcmd.twist_cmd.twist.linear.x = xdecition.speed()/3.6;
|
|
|
+ xcmd.twist_cmd.twist.angular.z = 3.0* xdecition.wheelangle() /600.0;
|
|
|
+ xcmd.ctrl_cmd.linear_velocity = 30.0;
|
|
|
+ //xcmd.ctrl_cmd.steering_angle = xdecition.wheelangle() * (-1.0)/600.0;
|
|
|
+ //xcmd.gear_cmd.gear = 1;//autoware_msgs::VehicleCmd::_gear_cmd_type::NONE;
|
|
|
+ xcmd.mode = 1;
|
|
|
+ if(xdecition.leftlamp() == true)
|
|
|
+ {
|
|
|
+ xcmd.lamp_cmd.l = 1;
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ xcmd.lamp_cmd.l = 0;
|
|
|
+ }
|
|
|
+ if(xdecition.rightlamp() == true)
|
|
|
+ {
|
|
|
+ xcmd.lamp_cmd.r = 1;
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ xcmd.lamp_cmd.r = 0;
|
|
|
+ }
|
|
|
+ // xcmd.lamp_cmd.l = 0;
|
|
|
+ //xcmd.lamp_cmd.r = 0;
|
|
|
+
|
|
|
+
|
|
|
+ test_cmd_pub.publish(xcmd);
|
|
|
+}
|
|
|
+
|
|
|
int main(int argc, char *argv[])
|
|
|
{
|
|
|
ros::init(argc, argv, "rostopilot");
|
|
@@ -226,14 +275,15 @@ int main(int argc, char *argv[])
|
|
|
gpa_image = iv::modulecomm::RegisterSend(_image_msgname.data(),20000000,1);
|
|
|
gpa_odom = iv::modulecomm::RegisterSend(_odom_msgname.data(),10000,1);
|
|
|
|
|
|
- points_sub = private_nh.subscribe(_point_topic, 1, points_callback);
|
|
|
+ points_sub = private_nh.subscribe(_point_topic, 1, points_callback);
|
|
|
|
|
|
image_transport::ImageTransport it(private_nh);
|
|
|
image_transport::Subscriber sub = it.subscribe( _image_topic, 1, imageCalllback );
|
|
|
|
|
|
odom_sub = private_nh.subscribe(_odom_topic,1,odomCalllback);
|
|
|
|
|
|
- std::thread * pnew = new std::thread(testvh);
|
|
|
+ void * pdecition = iv::modulecomm::RegisterRecv("deciton",UpdateDecition);
|
|
|
+ // std::thread * pnew = new std::thread(testvh);
|
|
|
|
|
|
ros::spin();
|
|
|
/*
|