Browse Source

change pilot_autoware_bridge. add cmd msg.

yuchuli 1 year ago
parent
commit
0f99d17875

+ 2 - 1
src/ros2/src/pilot_autoware_bridge/CMakeLists.txt

@@ -37,6 +37,7 @@ include_directories(
 
 include_directories(
   ${CMAKE_CURRENT_SOURCE_DIR}/../include
+  ${CMAKE_CURRENT_SOURCE_DIR}/../include/pilot_autoware_bridge
   ${CMAKE_CURRENT_SOURCE_DIR}/../include/msgtype
 )
 link_directories(
@@ -50,7 +51,7 @@ add_executable(pilot_autoware_bridge
   ./../include/msgtype/gpsimu.pb.cc
 )
 
-target_link_libraries(pilot_autoware_bridge  ${Protobuf_LIBRARIES}  Geographic   Qt5Core Qt5Xml modulecomm)
+target_link_libraries(pilot_autoware_bridge  ${Protobuf_LIBRARIES}  Geographic  modulecomm )
 
 ament_target_dependencies(pilot_autoware_bridge rclcpp std_msgs geometry_msgs 
   tf2_geometry_msgs nav_msgs sensor_msgs autoware_auto_control_msgs autoware_auto_geometry_msgs

+ 7 - 0
src/ros2/src/pilot_autoware_bridge/include/pilot_autoware_bridge/pilot_autoware_bridge_core.hpp

@@ -66,6 +66,8 @@
 #include "tier4_autoware_utils/ros/msg_covariance.hpp"
 #include "tier4_autoware_utils/ros/update_param.hpp"
 
+#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
+
 #include "gpsimu.pb.h"
 
 #include "modulecomm.h"
@@ -97,6 +99,7 @@ using geometry_msgs::msg::Twist;
 using geometry_msgs::msg::TwistStamped;
 using nav_msgs::msg::Odometry;
 using sensor_msgs::msg::Imu;
+using autoware_auto_control_msgs::msg::AckermannControlCommand;
 
 class pilot_autoware_bridge : public rclcpp::Node
 {
@@ -124,6 +127,8 @@ private:
 
   rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr twist_pub_;
 
+  rclcpp::Subscription<AckermannControlCommand>::SharedPtr sub_cmd_;
+
 
 
 
@@ -158,6 +163,8 @@ private:
 
   SteeringReport current_steer_;
 
+  AckermannControlCommand::SharedPtr mpcmd_ptr;
+
   void * mpagpsimu;
 
 

+ 1 - 1
src/ros2/src/pilot_autoware_bridge/package.xml

@@ -10,7 +10,7 @@
 
   <buildtool_depend>ament_cmake</buildtool_depend>
 
-    <depend>autoware_auto_control_msgs</depend>
+  <depend>autoware_auto_control_msgs</depend>
   <depend>autoware_auto_mapping_msgs</depend>
   <depend>autoware_auto_planning_msgs</depend>
   <depend>autoware_auto_tf2</depend>

+ 6 - 2
src/ros2/src/pilot_autoware_bridge/src/pilot_autoware_bridge_core.cpp

@@ -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;