瀏覽代碼

前后车先到先进原则,精度及速度限制不再由上位机发送

zx 1 年之前
父節點
當前提交
c309d81c52

+ 2 - 2
MPC/loaded_mpc.cpp

@@ -178,8 +178,8 @@ MpcError LoadedMPC::solve(Trajectory trajectory, Pose2d target,Eigen::VectorXd s
   //根据当前点和目标点距离,计算目标速度
 
   double ref_velocity = Pose2d::distance(pose_agv, target) / 2.5;
-  if(ref_velocity<0.05)
-    ref_velocity=0.05;
+  if(ref_velocity<0.1)
+    ref_velocity=0.1;
   //目标点与起点的连线 朝向与启动朝向 > M_PI/2.0
 
   Pose2d targetPoseInAGV=Pose2d::relativePose(target,pose_agv);

+ 42 - 524
MPC/monitor/emqx/message.pb.cc

@@ -16,10 +16,9 @@
 #include <google/protobuf/port_def.inc>
 extern PROTOBUF_INTERNAL_EXPORT_message_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_AgvStatu_message_2eproto;
 extern PROTOBUF_INTERNAL_EXPORT_message_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_LidarOdomStatu_message_2eproto;
-extern PROTOBUF_INTERNAL_EXPORT_message_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<2> scc_info_NewAction_message_2eproto;
+extern PROTOBUF_INTERNAL_EXPORT_message_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<1> scc_info_NewAction_message_2eproto;
 extern PROTOBUF_INTERNAL_EXPORT_message_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_PathNode_message_2eproto;
 extern PROTOBUF_INTERNAL_EXPORT_message_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_Pose2d_message_2eproto;
-extern PROTOBUF_INTERNAL_EXPORT_message_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_SpeedLimit_message_2eproto;
 extern PROTOBUF_INTERNAL_EXPORT_message_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<1> scc_info_Trajectory_message_2eproto;
 namespace NavMessage {
 class LidarOdomStatuDefaultTypeInternal {
@@ -34,10 +33,6 @@ class ToAgvCmdDefaultTypeInternal {
  public:
   ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<ToAgvCmd> _instance;
 } _ToAgvCmd_default_instance_;
-class SpeedLimitDefaultTypeInternal {
- public:
-  ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<SpeedLimit> _instance;
-} _SpeedLimit_default_instance_;
 class Pose2dDefaultTypeInternal {
  public:
   ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<Pose2d> _instance;
@@ -137,10 +132,9 @@ static void InitDefaultsscc_info_NewAction_message_2eproto() {
   ::NavMessage::NewAction::InitAsDefaultInstance();
 }
 
-::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<2> scc_info_NewAction_message_2eproto =
-    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 2, 0, InitDefaultsscc_info_NewAction_message_2eproto}, {
-      &scc_info_PathNode_message_2eproto.base,
-      &scc_info_SpeedLimit_message_2eproto.base,}};
+::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<1> scc_info_NewAction_message_2eproto =
+    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 1, 0, InitDefaultsscc_info_NewAction_message_2eproto}, {
+      &scc_info_PathNode_message_2eproto.base,}};
 
 static void InitDefaultsscc_info_PathNode_message_2eproto() {
   GOOGLE_PROTOBUF_VERIFY_VERSION;
@@ -185,20 +179,6 @@ static void InitDefaultsscc_info_RobotStatu_message_2eproto() {
     {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 1, 0, InitDefaultsscc_info_RobotStatu_message_2eproto}, {
       &scc_info_AgvStatu_message_2eproto.base,}};
 
-static void InitDefaultsscc_info_SpeedLimit_message_2eproto() {
-  GOOGLE_PROTOBUF_VERIFY_VERSION;
-
-  {
-    void* ptr = &::NavMessage::_SpeedLimit_default_instance_;
-    new (ptr) ::NavMessage::SpeedLimit();
-    ::PROTOBUF_NAMESPACE_ID::internal::OnShutdownDestroyMessage(ptr);
-  }
-  ::NavMessage::SpeedLimit::InitAsDefaultInstance();
-}
-
-::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_SpeedLimit_message_2eproto =
-    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 0, 0, InitDefaultsscc_info_SpeedLimit_message_2eproto}, {}};
-
 static void InitDefaultsscc_info_ToAgvCmd_message_2eproto() {
   GOOGLE_PROTOBUF_VERIFY_VERSION;
 
@@ -228,7 +208,7 @@ static void InitDefaultsscc_info_Trajectory_message_2eproto() {
     {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 1, 0, InitDefaultsscc_info_Trajectory_message_2eproto}, {
       &scc_info_Pose2d_message_2eproto.base,}};
 
-static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_message_2eproto[11];
+static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_message_2eproto[10];
 static constexpr ::PROTOBUF_NAMESPACE_ID::EnumDescriptor const** file_level_enum_descriptors_message_2eproto = nullptr;
 static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_message_2eproto = nullptr;
 
@@ -265,13 +245,6 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_message_2eproto::offsets[] PRO
   PROTOBUF_FIELD_OFFSET(::NavMessage::ToAgvCmd, l_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::ToAgvCmd, end_),
   ~0u,  // no _has_bits_
-  PROTOBUF_FIELD_OFFSET(::NavMessage::SpeedLimit, _internal_metadata_),
-  ~0u,  // no _extensions_
-  ~0u,  // no _oneof_case_
-  ~0u,  // no _weak_field_map_
-  PROTOBUF_FIELD_OFFSET(::NavMessage::SpeedLimit, min_),
-  PROTOBUF_FIELD_OFFSET(::NavMessage::SpeedLimit, max_),
-  ~0u,  // no _has_bits_
   PROTOBUF_FIELD_OFFSET(::NavMessage::Pose2d, _internal_metadata_),
   ~0u,  // no _extensions_
   ~0u,  // no _oneof_case_
@@ -306,11 +279,6 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_message_2eproto::offsets[] PRO
   PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, passnode_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, streetnode_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, pathnodes_),
-  PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, inoutvlimit_),
-  PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, nodevelocitylimit_),
-  PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, nodeangularlimit_),
-  PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, adjustvelocitylimit_),
-  PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, adjusthorizonlimit_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, wheelbase_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::NewAction, changedmode_),
   ~0u,  // no _has_bits_
@@ -349,21 +317,19 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB
   { 0, -1, sizeof(::NavMessage::LidarOdomStatu)},
   { 10, -1, sizeof(::NavMessage::AgvStatu)},
   { 19, -1, sizeof(::NavMessage::ToAgvCmd)},
-  { 31, -1, sizeof(::NavMessage::SpeedLimit)},
-  { 38, -1, sizeof(::NavMessage::Pose2d)},
-  { 46, -1, sizeof(::NavMessage::PathNode)},
-  { 57, -1, sizeof(::NavMessage::Trajectory)},
-  { 63, -1, sizeof(::NavMessage::NewAction)},
-  { 80, -1, sizeof(::NavMessage::NavCmd)},
-  { 88, -1, sizeof(::NavMessage::NavStatu)},
-  { 102, -1, sizeof(::NavMessage::RobotStatu)},
+  { 31, -1, sizeof(::NavMessage::Pose2d)},
+  { 39, -1, sizeof(::NavMessage::PathNode)},
+  { 50, -1, sizeof(::NavMessage::Trajectory)},
+  { 56, -1, sizeof(::NavMessage::NewAction)},
+  { 68, -1, sizeof(::NavMessage::NavCmd)},
+  { 76, -1, sizeof(::NavMessage::NavStatu)},
+  { 90, -1, sizeof(::NavMessage::RobotStatu)},
 };
 
 static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = {
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavMessage::_LidarOdomStatu_default_instance_),
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavMessage::_AgvStatu_default_instance_),
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavMessage::_ToAgvCmd_default_instance_),
-  reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavMessage::_SpeedLimit_default_instance_),
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavMessage::_Pose2d_default_instance_),
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavMessage::_PathNode_default_instance_),
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavMessage::_Trajectory_default_instance_),
@@ -380,39 +346,32 @@ const char descriptor_table_protodef_message_2eproto[] PROTOBUF_SECTION_VARIABLE
   "\n\001v\030\001 \001(\002\022\t\n\001w\030\002 \001(\002\022\r\n\005clamp\030\003 \001(\005\022\023\n\013c"
   "lamp_other\030\004 \001(\005\"Y\n\010ToAgvCmd\022\t\n\001H\030\001 \001(\005\022"
   "\t\n\001M\030\002 \001(\005\022\t\n\001T\030\003 \001(\005\022\t\n\001V\030\004 \001(\002\022\t\n\001W\030\005 "
-  "\001(\002\022\t\n\001L\030\006 \001(\002\022\013\n\003end\030\007 \001(\005\"&\n\nSpeedLimi"
-  "t\022\013\n\003min\030\001 \001(\002\022\013\n\003max\030\002 \001(\002\"-\n\006Pose2d\022\t\n"
+  "\001(\002\022\t\n\001L\030\006 \001(\002\022\013\n\003end\030\007 \001(\005\"-\n\006Pose2d\022\t\n"
   "\001x\030\001 \001(\002\022\t\n\001y\030\002 \001(\002\022\r\n\005theta\030\003 \001(\002\"Q\n\010Pa"
   "thNode\022\t\n\001x\030\001 \001(\002\022\t\n\001y\030\002 \001(\002\022\t\n\001l\030\003 \001(\002\022"
   "\t\n\001w\030\004 \001(\002\022\r\n\005theta\030\005 \001(\002\022\n\n\002id\030\006 \001(\t\"/\n"
   "\nTrajectory\022!\n\005poses\030\001 \003(\0132\022.NavMessage."
-  "Pose2d\"\340\003\n\tNewAction\022\014\n\004type\030\001 \001(\005\022\'\n\tsp"
+  "Pose2d\"\345\001\n\tNewAction\022\014\n\004type\030\001 \001(\005\022\'\n\tsp"
   "aceNode\030\002 \001(\0132\024.NavMessage.PathNode\022&\n\010p"
   "assNode\030\003 \001(\0132\024.NavMessage.PathNode\022(\n\ns"
   "treetNode\030\004 \001(\0132\024.NavMessage.PathNode\022\'\n"
-  "\tpathNodes\030\005 \003(\0132\024.NavMessage.PathNode\022+"
-  "\n\013InOutVLimit\030\006 \001(\0132\026.NavMessage.SpeedLi"
-  "mit\0221\n\021NodeVelocityLimit\030\007 \001(\0132\026.NavMess"
-  "age.SpeedLimit\0220\n\020NodeAngularLimit\030\010 \001(\013"
-  "2\026.NavMessage.SpeedLimit\0223\n\023adjustVeloci"
-  "tylimit\030\t \001(\0132\026.NavMessage.SpeedLimit\0222\n"
-  "\022adjustHorizonLimit\030\n \001(\0132\026.NavMessage.S"
-  "peedLimit\022\021\n\twheelbase\030\013 \001(\002\022\023\n\013changedM"
-  "ode\030\014 \001(\005\"P\n\006NavCmd\022\016\n\006action\030\001 \001(\005\022\013\n\003k"
-  "ey\030\002 \001(\t\022)\n\nnewActions\030\005 \003(\0132\025.NavMessag"
-  "e.NewAction\"\366\001\n\010NavStatu\022\r\n\005statu\030\001 \001(\005\022"
-  "\020\n\010main_agv\030\002 \001(\010\022\021\n\tmove_mode\030\003 \001(\005\022(\n\004"
-  "odom\030\004 \001(\0132\032.NavMessage.LidarOdomStatu\022\013"
-  "\n\003key\030\005 \001(\t\022-\n\rselected_traj\030\006 \001(\0132\026.Nav"
-  "Message.Trajectory\022,\n\014predict_traj\030\007 \001(\013"
-  "2\026.NavMessage.Trajectory\022\020\n\010in_space\030\010 \001"
-  "(\010\022\020\n\010space_id\030\t \001(\t\"Y\n\nRobotStatu\022\t\n\001x\030"
-  "\001 \001(\002\022\t\n\001y\030\002 \001(\002\022\r\n\005theta\030\003 \001(\002\022&\n\010agvSt"
-  "atu\030\004 \001(\0132\024.NavMessage.AgvStatub\006proto3"
+  "\tpathNodes\030\005 \003(\0132\024.NavMessage.PathNode\022\021"
+  "\n\twheelbase\030\006 \001(\002\022\023\n\013changedMode\030\007 \001(\005\"P"
+  "\n\006NavCmd\022\016\n\006action\030\001 \001(\005\022\013\n\003key\030\002 \001(\t\022)\n"
+  "\nnewActions\030\005 \003(\0132\025.NavMessage.NewAction"
+  "\"\366\001\n\010NavStatu\022\r\n\005statu\030\001 \001(\005\022\020\n\010main_agv"
+  "\030\002 \001(\010\022\021\n\tmove_mode\030\003 \001(\005\022(\n\004odom\030\004 \001(\0132"
+  "\032.NavMessage.LidarOdomStatu\022\013\n\003key\030\005 \001(\t"
+  "\022-\n\rselected_traj\030\006 \001(\0132\026.NavMessage.Tra"
+  "jectory\022,\n\014predict_traj\030\007 \001(\0132\026.NavMessa"
+  "ge.Trajectory\022\020\n\010in_space\030\010 \001(\010\022\020\n\010space"
+  "_id\030\t \001(\t\"Y\n\nRobotStatu\022\t\n\001x\030\001 \001(\002\022\t\n\001y\030"
+  "\002 \001(\002\022\r\n\005theta\030\003 \001(\002\022&\n\010agvStatu\030\004 \001(\0132\024"
+  ".NavMessage.AgvStatub\006proto3"
   ;
 static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_message_2eproto_deps[1] = {
 };
-static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_message_2eproto_sccs[11] = {
+static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_message_2eproto_sccs[10] = {
   &scc_info_AgvStatu_message_2eproto.base,
   &scc_info_LidarOdomStatu_message_2eproto.base,
   &scc_info_NavCmd_message_2eproto.base,
@@ -421,16 +380,15 @@ static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_mes
   &scc_info_PathNode_message_2eproto.base,
   &scc_info_Pose2d_message_2eproto.base,
   &scc_info_RobotStatu_message_2eproto.base,
-  &scc_info_SpeedLimit_message_2eproto.base,
   &scc_info_ToAgvCmd_message_2eproto.base,
   &scc_info_Trajectory_message_2eproto.base,
 };
 static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_message_2eproto_once;
 const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_message_2eproto = {
-  false, false, descriptor_table_protodef_message_2eproto, "message.proto", 1399,
-  &descriptor_table_message_2eproto_once, descriptor_table_message_2eproto_sccs, descriptor_table_message_2eproto_deps, 11, 0,
+  false, false, descriptor_table_protodef_message_2eproto, "message.proto", 1108,
+  &descriptor_table_message_2eproto_once, descriptor_table_message_2eproto_sccs, descriptor_table_message_2eproto_deps, 10, 0,
   schemas, file_default_instances, TableStruct_message_2eproto::offsets,
-  file_level_metadata_message_2eproto, 11, file_level_enum_descriptors_message_2eproto, file_level_service_descriptors_message_2eproto,
+  file_level_metadata_message_2eproto, 10, file_level_enum_descriptors_message_2eproto, file_level_service_descriptors_message_2eproto,
 };
 
 // Force running AddDescriptors() at dynamic initialization time.
@@ -1340,233 +1298,6 @@ void ToAgvCmd::InternalSwap(ToAgvCmd* other) {
 }
 
 
-// ===================================================================
-
-void SpeedLimit::InitAsDefaultInstance() {
-}
-class SpeedLimit::_Internal {
- public:
-};
-
-SpeedLimit::SpeedLimit(::PROTOBUF_NAMESPACE_ID::Arena* arena)
-  : ::PROTOBUF_NAMESPACE_ID::Message(arena) {
-  SharedCtor();
-  RegisterArenaDtor(arena);
-  // @@protoc_insertion_point(arena_constructor:NavMessage.SpeedLimit)
-}
-SpeedLimit::SpeedLimit(const SpeedLimit& from)
-  : ::PROTOBUF_NAMESPACE_ID::Message() {
-  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
-  ::memcpy(&min_, &from.min_,
-    static_cast<size_t>(reinterpret_cast<char*>(&max_) -
-    reinterpret_cast<char*>(&min_)) + sizeof(max_));
-  // @@protoc_insertion_point(copy_constructor:NavMessage.SpeedLimit)
-}
-
-void SpeedLimit::SharedCtor() {
-  ::memset(&min_, 0, static_cast<size_t>(
-      reinterpret_cast<char*>(&max_) -
-      reinterpret_cast<char*>(&min_)) + sizeof(max_));
-}
-
-SpeedLimit::~SpeedLimit() {
-  // @@protoc_insertion_point(destructor:NavMessage.SpeedLimit)
-  SharedDtor();
-  _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-}
-
-void SpeedLimit::SharedDtor() {
-  GOOGLE_DCHECK(GetArena() == nullptr);
-}
-
-void SpeedLimit::ArenaDtor(void* object) {
-  SpeedLimit* _this = reinterpret_cast< SpeedLimit* >(object);
-  (void)_this;
-}
-void SpeedLimit::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) {
-}
-void SpeedLimit::SetCachedSize(int size) const {
-  _cached_size_.Set(size);
-}
-const SpeedLimit& SpeedLimit::default_instance() {
-  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&::scc_info_SpeedLimit_message_2eproto.base);
-  return *internal_default_instance();
-}
-
-
-void SpeedLimit::Clear() {
-// @@protoc_insertion_point(message_clear_start:NavMessage.SpeedLimit)
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  // Prevent compiler warnings about cached_has_bits being unused
-  (void) cached_has_bits;
-
-  ::memset(&min_, 0, static_cast<size_t>(
-      reinterpret_cast<char*>(&max_) -
-      reinterpret_cast<char*>(&min_)) + sizeof(max_));
-  _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
-}
-
-const char* SpeedLimit::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) {
-#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure
-  ::PROTOBUF_NAMESPACE_ID::Arena* arena = GetArena(); (void)arena;
-  while (!ctx->Done(&ptr)) {
-    ::PROTOBUF_NAMESPACE_ID::uint32 tag;
-    ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag);
-    CHK_(ptr);
-    switch (tag >> 3) {
-      // float min = 1;
-      case 1:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 13)) {
-          min_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
-          ptr += sizeof(float);
-        } else goto handle_unusual;
-        continue;
-      // float max = 2;
-      case 2:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 21)) {
-          max_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
-          ptr += sizeof(float);
-        } else goto handle_unusual;
-        continue;
-      default: {
-      handle_unusual:
-        if ((tag & 7) == 4 || tag == 0) {
-          ctx->SetLastTag(tag);
-          goto success;
-        }
-        ptr = UnknownFieldParse(tag,
-            _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(),
-            ptr, ctx);
-        CHK_(ptr != nullptr);
-        continue;
-      }
-    }  // switch
-  }  // while
-success:
-  return ptr;
-failure:
-  ptr = nullptr;
-  goto success;
-#undef CHK_
-}
-
-::PROTOBUF_NAMESPACE_ID::uint8* SpeedLimit::_InternalSerialize(
-    ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const {
-  // @@protoc_insertion_point(serialize_to_array_start:NavMessage.SpeedLimit)
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  (void) cached_has_bits;
-
-  // float min = 1;
-  if (!(this->min() <= 0 && this->min() >= 0)) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_min(), target);
-  }
-
-  // float max = 2;
-  if (!(this->max() <= 0 && this->max() >= 0)) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(2, this->_internal_max(), target);
-  }
-
-  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
-        _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
-  }
-  // @@protoc_insertion_point(serialize_to_array_end:NavMessage.SpeedLimit)
-  return target;
-}
-
-size_t SpeedLimit::ByteSizeLong() const {
-// @@protoc_insertion_point(message_byte_size_start:NavMessage.SpeedLimit)
-  size_t total_size = 0;
-
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  // Prevent compiler warnings about cached_has_bits being unused
-  (void) cached_has_bits;
-
-  // float min = 1;
-  if (!(this->min() <= 0 && this->min() >= 0)) {
-    total_size += 1 + 4;
-  }
-
-  // float max = 2;
-  if (!(this->max() <= 0 && this->max() >= 0)) {
-    total_size += 1 + 4;
-  }
-
-  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
-    return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize(
-        _internal_metadata_, total_size, &_cached_size_);
-  }
-  int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size);
-  SetCachedSize(cached_size);
-  return total_size;
-}
-
-void SpeedLimit::MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
-// @@protoc_insertion_point(generalized_merge_from_start:NavMessage.SpeedLimit)
-  GOOGLE_DCHECK_NE(&from, this);
-  const SpeedLimit* source =
-      ::PROTOBUF_NAMESPACE_ID::DynamicCastToGenerated<SpeedLimit>(
-          &from);
-  if (source == nullptr) {
-  // @@protoc_insertion_point(generalized_merge_from_cast_fail:NavMessage.SpeedLimit)
-    ::PROTOBUF_NAMESPACE_ID::internal::ReflectionOps::Merge(from, this);
-  } else {
-  // @@protoc_insertion_point(generalized_merge_from_cast_success:NavMessage.SpeedLimit)
-    MergeFrom(*source);
-  }
-}
-
-void SpeedLimit::MergeFrom(const SpeedLimit& from) {
-// @@protoc_insertion_point(class_specific_merge_from_start:NavMessage.SpeedLimit)
-  GOOGLE_DCHECK_NE(&from, this);
-  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
-  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
-  (void) cached_has_bits;
-
-  if (!(from.min() <= 0 && from.min() >= 0)) {
-    _internal_set_min(from._internal_min());
-  }
-  if (!(from.max() <= 0 && from.max() >= 0)) {
-    _internal_set_max(from._internal_max());
-  }
-}
-
-void SpeedLimit::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
-// @@protoc_insertion_point(generalized_copy_from_start:NavMessage.SpeedLimit)
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-void SpeedLimit::CopyFrom(const SpeedLimit& from) {
-// @@protoc_insertion_point(class_specific_copy_from_start:NavMessage.SpeedLimit)
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-bool SpeedLimit::IsInitialized() const {
-  return true;
-}
-
-void SpeedLimit::InternalSwap(SpeedLimit* other) {
-  using std::swap;
-  _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
-  ::PROTOBUF_NAMESPACE_ID::internal::memswap<
-      PROTOBUF_FIELD_OFFSET(SpeedLimit, max_)
-      + sizeof(SpeedLimit::max_)
-      - PROTOBUF_FIELD_OFFSET(SpeedLimit, min_)>(
-          reinterpret_cast<char*>(&min_),
-          reinterpret_cast<char*>(&other->min_));
-}
-
-::PROTOBUF_NAMESPACE_ID::Metadata SpeedLimit::GetMetadata() const {
-  return GetMetadataStatic();
-}
-
-
 // ===================================================================
 
 void Pose2d::InitAsDefaultInstance() {
@@ -2356,27 +2087,12 @@ void NewAction::InitAsDefaultInstance() {
       ::NavMessage::PathNode::internal_default_instance());
   ::NavMessage::_NewAction_default_instance_._instance.get_mutable()->streetnode_ = const_cast< ::NavMessage::PathNode*>(
       ::NavMessage::PathNode::internal_default_instance());
-  ::NavMessage::_NewAction_default_instance_._instance.get_mutable()->inoutvlimit_ = const_cast< ::NavMessage::SpeedLimit*>(
-      ::NavMessage::SpeedLimit::internal_default_instance());
-  ::NavMessage::_NewAction_default_instance_._instance.get_mutable()->nodevelocitylimit_ = const_cast< ::NavMessage::SpeedLimit*>(
-      ::NavMessage::SpeedLimit::internal_default_instance());
-  ::NavMessage::_NewAction_default_instance_._instance.get_mutable()->nodeangularlimit_ = const_cast< ::NavMessage::SpeedLimit*>(
-      ::NavMessage::SpeedLimit::internal_default_instance());
-  ::NavMessage::_NewAction_default_instance_._instance.get_mutable()->adjustvelocitylimit_ = const_cast< ::NavMessage::SpeedLimit*>(
-      ::NavMessage::SpeedLimit::internal_default_instance());
-  ::NavMessage::_NewAction_default_instance_._instance.get_mutable()->adjusthorizonlimit_ = const_cast< ::NavMessage::SpeedLimit*>(
-      ::NavMessage::SpeedLimit::internal_default_instance());
 }
 class NewAction::_Internal {
  public:
   static const ::NavMessage::PathNode& spacenode(const NewAction* msg);
   static const ::NavMessage::PathNode& passnode(const NewAction* msg);
   static const ::NavMessage::PathNode& streetnode(const NewAction* msg);
-  static const ::NavMessage::SpeedLimit& inoutvlimit(const NewAction* msg);
-  static const ::NavMessage::SpeedLimit& nodevelocitylimit(const NewAction* msg);
-  static const ::NavMessage::SpeedLimit& nodeangularlimit(const NewAction* msg);
-  static const ::NavMessage::SpeedLimit& adjustvelocitylimit(const NewAction* msg);
-  static const ::NavMessage::SpeedLimit& adjusthorizonlimit(const NewAction* msg);
 };
 
 const ::NavMessage::PathNode&
@@ -2391,26 +2107,6 @@ const ::NavMessage::PathNode&
 NewAction::_Internal::streetnode(const NewAction* msg) {
   return *msg->streetnode_;
 }
-const ::NavMessage::SpeedLimit&
-NewAction::_Internal::inoutvlimit(const NewAction* msg) {
-  return *msg->inoutvlimit_;
-}
-const ::NavMessage::SpeedLimit&
-NewAction::_Internal::nodevelocitylimit(const NewAction* msg) {
-  return *msg->nodevelocitylimit_;
-}
-const ::NavMessage::SpeedLimit&
-NewAction::_Internal::nodeangularlimit(const NewAction* msg) {
-  return *msg->nodeangularlimit_;
-}
-const ::NavMessage::SpeedLimit&
-NewAction::_Internal::adjustvelocitylimit(const NewAction* msg) {
-  return *msg->adjustvelocitylimit_;
-}
-const ::NavMessage::SpeedLimit&
-NewAction::_Internal::adjusthorizonlimit(const NewAction* msg) {
-  return *msg->adjusthorizonlimit_;
-}
 NewAction::NewAction(::PROTOBUF_NAMESPACE_ID::Arena* arena)
   : ::PROTOBUF_NAMESPACE_ID::Message(arena),
   pathnodes_(arena) {
@@ -2437,31 +2133,6 @@ NewAction::NewAction(const NewAction& from)
   } else {
     streetnode_ = nullptr;
   }
-  if (from._internal_has_inoutvlimit()) {
-    inoutvlimit_ = new ::NavMessage::SpeedLimit(*from.inoutvlimit_);
-  } else {
-    inoutvlimit_ = nullptr;
-  }
-  if (from._internal_has_nodevelocitylimit()) {
-    nodevelocitylimit_ = new ::NavMessage::SpeedLimit(*from.nodevelocitylimit_);
-  } else {
-    nodevelocitylimit_ = nullptr;
-  }
-  if (from._internal_has_nodeangularlimit()) {
-    nodeangularlimit_ = new ::NavMessage::SpeedLimit(*from.nodeangularlimit_);
-  } else {
-    nodeangularlimit_ = nullptr;
-  }
-  if (from._internal_has_adjustvelocitylimit()) {
-    adjustvelocitylimit_ = new ::NavMessage::SpeedLimit(*from.adjustvelocitylimit_);
-  } else {
-    adjustvelocitylimit_ = nullptr;
-  }
-  if (from._internal_has_adjusthorizonlimit()) {
-    adjusthorizonlimit_ = new ::NavMessage::SpeedLimit(*from.adjusthorizonlimit_);
-  } else {
-    adjusthorizonlimit_ = nullptr;
-  }
   ::memcpy(&type_, &from.type_,
     static_cast<size_t>(reinterpret_cast<char*>(&changedmode_) -
     reinterpret_cast<char*>(&type_)) + sizeof(changedmode_));
@@ -2486,11 +2157,6 @@ void NewAction::SharedDtor() {
   if (this != internal_default_instance()) delete spacenode_;
   if (this != internal_default_instance()) delete passnode_;
   if (this != internal_default_instance()) delete streetnode_;
-  if (this != internal_default_instance()) delete inoutvlimit_;
-  if (this != internal_default_instance()) delete nodevelocitylimit_;
-  if (this != internal_default_instance()) delete nodeangularlimit_;
-  if (this != internal_default_instance()) delete adjustvelocitylimit_;
-  if (this != internal_default_instance()) delete adjusthorizonlimit_;
 }
 
 void NewAction::ArenaDtor(void* object) {
@@ -2527,26 +2193,6 @@ void NewAction::Clear() {
     delete streetnode_;
   }
   streetnode_ = nullptr;
-  if (GetArena() == nullptr && inoutvlimit_ != nullptr) {
-    delete inoutvlimit_;
-  }
-  inoutvlimit_ = nullptr;
-  if (GetArena() == nullptr && nodevelocitylimit_ != nullptr) {
-    delete nodevelocitylimit_;
-  }
-  nodevelocitylimit_ = nullptr;
-  if (GetArena() == nullptr && nodeangularlimit_ != nullptr) {
-    delete nodeangularlimit_;
-  }
-  nodeangularlimit_ = nullptr;
-  if (GetArena() == nullptr && adjustvelocitylimit_ != nullptr) {
-    delete adjustvelocitylimit_;
-  }
-  adjustvelocitylimit_ = nullptr;
-  if (GetArena() == nullptr && adjusthorizonlimit_ != nullptr) {
-    delete adjusthorizonlimit_;
-  }
-  adjusthorizonlimit_ = nullptr;
   ::memset(&type_, 0, static_cast<size_t>(
       reinterpret_cast<char*>(&changedmode_) -
       reinterpret_cast<char*>(&type_)) + sizeof(changedmode_));
@@ -2601,51 +2247,16 @@ const char* NewAction::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::
           } while (::PROTOBUF_NAMESPACE_ID::internal::ExpectTag<42>(ptr));
         } else goto handle_unusual;
         continue;
-      // .NavMessage.SpeedLimit InOutVLimit = 6;
+      // float wheelbase = 6;
       case 6:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 50)) {
-          ptr = ctx->ParseMessage(_internal_mutable_inoutvlimit(), ptr);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      // .NavMessage.SpeedLimit NodeVelocityLimit = 7;
-      case 7:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 58)) {
-          ptr = ctx->ParseMessage(_internal_mutable_nodevelocitylimit(), ptr);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      // .NavMessage.SpeedLimit NodeAngularLimit = 8;
-      case 8:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 66)) {
-          ptr = ctx->ParseMessage(_internal_mutable_nodeangularlimit(), ptr);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      // .NavMessage.SpeedLimit adjustVelocitylimit = 9;
-      case 9:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 74)) {
-          ptr = ctx->ParseMessage(_internal_mutable_adjustvelocitylimit(), ptr);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      // .NavMessage.SpeedLimit adjustHorizonLimit = 10;
-      case 10:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 82)) {
-          ptr = ctx->ParseMessage(_internal_mutable_adjusthorizonlimit(), ptr);
-          CHK_(ptr);
-        } else goto handle_unusual;
-        continue;
-      // float wheelbase = 11;
-      case 11:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 93)) {
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 53)) {
           wheelbase_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
           ptr += sizeof(float);
         } else goto handle_unusual;
         continue;
-      // int32 changedMode = 12;
-      case 12:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 96)) {
+      // int32 changedMode = 7;
+      case 7:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 56)) {
           changedmode_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
           CHK_(ptr);
         } else goto handle_unusual;
@@ -2716,56 +2327,16 @@ failure:
       InternalWriteMessage(5, this->_internal_pathnodes(i), target, stream);
   }
 
-  // .NavMessage.SpeedLimit InOutVLimit = 6;
-  if (this->has_inoutvlimit()) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
-      InternalWriteMessage(
-        6, _Internal::inoutvlimit(this), target, stream);
-  }
-
-  // .NavMessage.SpeedLimit NodeVelocityLimit = 7;
-  if (this->has_nodevelocitylimit()) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
-      InternalWriteMessage(
-        7, _Internal::nodevelocitylimit(this), target, stream);
-  }
-
-  // .NavMessage.SpeedLimit NodeAngularLimit = 8;
-  if (this->has_nodeangularlimit()) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
-      InternalWriteMessage(
-        8, _Internal::nodeangularlimit(this), target, stream);
-  }
-
-  // .NavMessage.SpeedLimit adjustVelocitylimit = 9;
-  if (this->has_adjustvelocitylimit()) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
-      InternalWriteMessage(
-        9, _Internal::adjustvelocitylimit(this), target, stream);
-  }
-
-  // .NavMessage.SpeedLimit adjustHorizonLimit = 10;
-  if (this->has_adjusthorizonlimit()) {
-    target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
-      InternalWriteMessage(
-        10, _Internal::adjusthorizonlimit(this), target, stream);
-  }
-
-  // float wheelbase = 11;
+  // float wheelbase = 6;
   if (!(this->wheelbase() <= 0 && this->wheelbase() >= 0)) {
     target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(11, this->_internal_wheelbase(), target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(6, this->_internal_wheelbase(), target);
   }
 
-  // int32 changedMode = 12;
+  // int32 changedMode = 7;
   if (this->changedmode() != 0) {
     target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(12, this->_internal_changedmode(), target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(7, this->_internal_changedmode(), target);
   }
 
   if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
@@ -2812,41 +2383,6 @@ size_t NewAction::ByteSizeLong() const {
         *streetnode_);
   }
 
-  // .NavMessage.SpeedLimit InOutVLimit = 6;
-  if (this->has_inoutvlimit()) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
-        *inoutvlimit_);
-  }
-
-  // .NavMessage.SpeedLimit NodeVelocityLimit = 7;
-  if (this->has_nodevelocitylimit()) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
-        *nodevelocitylimit_);
-  }
-
-  // .NavMessage.SpeedLimit NodeAngularLimit = 8;
-  if (this->has_nodeangularlimit()) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
-        *nodeangularlimit_);
-  }
-
-  // .NavMessage.SpeedLimit adjustVelocitylimit = 9;
-  if (this->has_adjustvelocitylimit()) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
-        *adjustvelocitylimit_);
-  }
-
-  // .NavMessage.SpeedLimit adjustHorizonLimit = 10;
-  if (this->has_adjusthorizonlimit()) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
-        *adjusthorizonlimit_);
-  }
-
   // int32 type = 1;
   if (this->type() != 0) {
     total_size += 1 +
@@ -2854,12 +2390,12 @@ size_t NewAction::ByteSizeLong() const {
         this->_internal_type());
   }
 
-  // float wheelbase = 11;
+  // float wheelbase = 6;
   if (!(this->wheelbase() <= 0 && this->wheelbase() >= 0)) {
     total_size += 1 + 4;
   }
 
-  // int32 changedMode = 12;
+  // int32 changedMode = 7;
   if (this->changedmode() != 0) {
     total_size += 1 +
       ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
@@ -2907,21 +2443,6 @@ void NewAction::MergeFrom(const NewAction& from) {
   if (from.has_streetnode()) {
     _internal_mutable_streetnode()->::NavMessage::PathNode::MergeFrom(from._internal_streetnode());
   }
-  if (from.has_inoutvlimit()) {
-    _internal_mutable_inoutvlimit()->::NavMessage::SpeedLimit::MergeFrom(from._internal_inoutvlimit());
-  }
-  if (from.has_nodevelocitylimit()) {
-    _internal_mutable_nodevelocitylimit()->::NavMessage::SpeedLimit::MergeFrom(from._internal_nodevelocitylimit());
-  }
-  if (from.has_nodeangularlimit()) {
-    _internal_mutable_nodeangularlimit()->::NavMessage::SpeedLimit::MergeFrom(from._internal_nodeangularlimit());
-  }
-  if (from.has_adjustvelocitylimit()) {
-    _internal_mutable_adjustvelocitylimit()->::NavMessage::SpeedLimit::MergeFrom(from._internal_adjustvelocitylimit());
-  }
-  if (from.has_adjusthorizonlimit()) {
-    _internal_mutable_adjusthorizonlimit()->::NavMessage::SpeedLimit::MergeFrom(from._internal_adjusthorizonlimit());
-  }
   if (from.type() != 0) {
     _internal_set_type(from._internal_type());
   }
@@ -4015,9 +3536,6 @@ template<> PROTOBUF_NOINLINE ::NavMessage::AgvStatu* Arena::CreateMaybeMessage<
 template<> PROTOBUF_NOINLINE ::NavMessage::ToAgvCmd* Arena::CreateMaybeMessage< ::NavMessage::ToAgvCmd >(Arena* arena) {
   return Arena::CreateMessageInternal< ::NavMessage::ToAgvCmd >(arena);
 }
-template<> PROTOBUF_NOINLINE ::NavMessage::SpeedLimit* Arena::CreateMaybeMessage< ::NavMessage::SpeedLimit >(Arena* arena) {
-  return Arena::CreateMessageInternal< ::NavMessage::SpeedLimit >(arena);
-}
 template<> PROTOBUF_NOINLINE ::NavMessage::Pose2d* Arena::CreateMaybeMessage< ::NavMessage::Pose2d >(Arena* arena) {
   return Arena::CreateMessageInternal< ::NavMessage::Pose2d >(arena);
 }

+ 14 - 727
MPC/monitor/emqx/message.pb.h

@@ -47,7 +47,7 @@ struct TableStruct_message_2eproto {
     PROTOBUF_SECTION_VARIABLE(protodesc_cold);
   static const ::PROTOBUF_NAMESPACE_ID::internal::AuxiliaryParseTableField aux[]
     PROTOBUF_SECTION_VARIABLE(protodesc_cold);
-  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[11]
+  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[10]
     PROTOBUF_SECTION_VARIABLE(protodesc_cold);
   static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[];
   static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[];
@@ -79,9 +79,6 @@ extern Pose2dDefaultTypeInternal _Pose2d_default_instance_;
 class RobotStatu;
 class RobotStatuDefaultTypeInternal;
 extern RobotStatuDefaultTypeInternal _RobotStatu_default_instance_;
-class SpeedLimit;
-class SpeedLimitDefaultTypeInternal;
-extern SpeedLimitDefaultTypeInternal _SpeedLimit_default_instance_;
 class ToAgvCmd;
 class ToAgvCmdDefaultTypeInternal;
 extern ToAgvCmdDefaultTypeInternal _ToAgvCmd_default_instance_;
@@ -98,7 +95,6 @@ template<> ::NavMessage::NewAction* Arena::CreateMaybeMessage<::NavMessage::NewA
 template<> ::NavMessage::PathNode* Arena::CreateMaybeMessage<::NavMessage::PathNode>(Arena*);
 template<> ::NavMessage::Pose2d* Arena::CreateMaybeMessage<::NavMessage::Pose2d>(Arena*);
 template<> ::NavMessage::RobotStatu* Arena::CreateMaybeMessage<::NavMessage::RobotStatu>(Arena*);
-template<> ::NavMessage::SpeedLimit* Arena::CreateMaybeMessage<::NavMessage::SpeedLimit>(Arena*);
 template<> ::NavMessage::ToAgvCmd* Arena::CreateMaybeMessage<::NavMessage::ToAgvCmd>(Arena*);
 template<> ::NavMessage::Trajectory* Arena::CreateMaybeMessage<::NavMessage::Trajectory>(Arena*);
 PROTOBUF_NAMESPACE_CLOSE
@@ -660,154 +656,6 @@ class ToAgvCmd PROTOBUF_FINAL :
 };
 // -------------------------------------------------------------------
 
-class SpeedLimit PROTOBUF_FINAL :
-    public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:NavMessage.SpeedLimit) */ {
- public:
-  inline SpeedLimit() : SpeedLimit(nullptr) {}
-  virtual ~SpeedLimit();
-
-  SpeedLimit(const SpeedLimit& from);
-  SpeedLimit(SpeedLimit&& from) noexcept
-    : SpeedLimit() {
-    *this = ::std::move(from);
-  }
-
-  inline SpeedLimit& operator=(const SpeedLimit& from) {
-    CopyFrom(from);
-    return *this;
-  }
-  inline SpeedLimit& operator=(SpeedLimit&& from) noexcept {
-    if (GetArena() == from.GetArena()) {
-      if (this != &from) InternalSwap(&from);
-    } else {
-      CopyFrom(from);
-    }
-    return *this;
-  }
-
-  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() {
-    return GetDescriptor();
-  }
-  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() {
-    return GetMetadataStatic().descriptor;
-  }
-  static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() {
-    return GetMetadataStatic().reflection;
-  }
-  static const SpeedLimit& default_instance();
-
-  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
-  static inline const SpeedLimit* internal_default_instance() {
-    return reinterpret_cast<const SpeedLimit*>(
-               &_SpeedLimit_default_instance_);
-  }
-  static constexpr int kIndexInFileMessages =
-    3;
-
-  friend void swap(SpeedLimit& a, SpeedLimit& b) {
-    a.Swap(&b);
-  }
-  inline void Swap(SpeedLimit* other) {
-    if (other == this) return;
-    if (GetArena() == other->GetArena()) {
-      InternalSwap(other);
-    } else {
-      ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other);
-    }
-  }
-  void UnsafeArenaSwap(SpeedLimit* other) {
-    if (other == this) return;
-    GOOGLE_DCHECK(GetArena() == other->GetArena());
-    InternalSwap(other);
-  }
-
-  // implements Message ----------------------------------------------
-
-  inline SpeedLimit* New() const final {
-    return CreateMaybeMessage<SpeedLimit>(nullptr);
-  }
-
-  SpeedLimit* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final {
-    return CreateMaybeMessage<SpeedLimit>(arena);
-  }
-  void CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
-  void MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
-  void CopyFrom(const SpeedLimit& from);
-  void MergeFrom(const SpeedLimit& from);
-  PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final;
-  bool IsInitialized() const final;
-
-  size_t ByteSizeLong() const final;
-  const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final;
-  ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize(
-      ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final;
-  int GetCachedSize() const final { return _cached_size_.Get(); }
-
-  private:
-  inline void SharedCtor();
-  inline void SharedDtor();
-  void SetCachedSize(int size) const final;
-  void InternalSwap(SpeedLimit* other);
-  friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata;
-  static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() {
-    return "NavMessage.SpeedLimit";
-  }
-  protected:
-  explicit SpeedLimit(::PROTOBUF_NAMESPACE_ID::Arena* arena);
-  private:
-  static void ArenaDtor(void* object);
-  inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena);
-  public:
-
-  ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final;
-  private:
-  static ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadataStatic() {
-    ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&::descriptor_table_message_2eproto);
-    return ::descriptor_table_message_2eproto.file_level_metadata[kIndexInFileMessages];
-  }
-
-  public:
-
-  // nested types ----------------------------------------------------
-
-  // accessors -------------------------------------------------------
-
-  enum : int {
-    kMinFieldNumber = 1,
-    kMaxFieldNumber = 2,
-  };
-  // float min = 1;
-  void clear_min();
-  float min() const;
-  void set_min(float value);
-  private:
-  float _internal_min() const;
-  void _internal_set_min(float value);
-  public:
-
-  // float max = 2;
-  void clear_max();
-  float max() const;
-  void set_max(float value);
-  private:
-  float _internal_max() const;
-  void _internal_set_max(float value);
-  public:
-
-  // @@protoc_insertion_point(class_scope:NavMessage.SpeedLimit)
- private:
-  class _Internal;
-
-  template <typename T> friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper;
-  typedef void InternalArenaConstructable_;
-  typedef void DestructorSkippable_;
-  float min_;
-  float max_;
-  mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
-  friend struct ::TableStruct_message_2eproto;
-};
-// -------------------------------------------------------------------
-
 class Pose2d PROTOBUF_FINAL :
     public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:NavMessage.Pose2d) */ {
  public:
@@ -850,7 +698,7 @@ class Pose2d PROTOBUF_FINAL :
                &_Pose2d_default_instance_);
   }
   static constexpr int kIndexInFileMessages =
-    4;
+    3;
 
   friend void swap(Pose2d& a, Pose2d& b) {
     a.Swap(&b);
@@ -1009,7 +857,7 @@ class PathNode PROTOBUF_FINAL :
                &_PathNode_default_instance_);
   }
   static constexpr int kIndexInFileMessages =
-    5;
+    4;
 
   friend void swap(PathNode& a, PathNode& b) {
     a.Swap(&b);
@@ -1208,7 +1056,7 @@ class Trajectory PROTOBUF_FINAL :
                &_Trajectory_default_instance_);
   }
   static constexpr int kIndexInFileMessages =
-    6;
+    5;
 
   friend void swap(Trajectory& a, Trajectory& b) {
     a.Swap(&b);
@@ -1354,7 +1202,7 @@ class NewAction PROTOBUF_FINAL :
                &_NewAction_default_instance_);
   }
   static constexpr int kIndexInFileMessages =
-    7;
+    6;
 
   friend void swap(NewAction& a, NewAction& b) {
     a.Swap(&b);
@@ -1429,14 +1277,9 @@ class NewAction PROTOBUF_FINAL :
     kSpaceNodeFieldNumber = 2,
     kPassNodeFieldNumber = 3,
     kStreetNodeFieldNumber = 4,
-    kInOutVLimitFieldNumber = 6,
-    kNodeVelocityLimitFieldNumber = 7,
-    kNodeAngularLimitFieldNumber = 8,
-    kAdjustVelocitylimitFieldNumber = 9,
-    kAdjustHorizonLimitFieldNumber = 10,
     kTypeFieldNumber = 1,
-    kWheelbaseFieldNumber = 11,
-    kChangedModeFieldNumber = 12,
+    kWheelbaseFieldNumber = 6,
+    kChangedModeFieldNumber = 7,
   };
   // repeated .NavMessage.PathNode pathNodes = 5;
   int pathnodes_size() const;
@@ -1510,96 +1353,6 @@ class NewAction PROTOBUF_FINAL :
       ::NavMessage::PathNode* streetnode);
   ::NavMessage::PathNode* unsafe_arena_release_streetnode();
 
-  // .NavMessage.SpeedLimit InOutVLimit = 6;
-  bool has_inoutvlimit() const;
-  private:
-  bool _internal_has_inoutvlimit() const;
-  public:
-  void clear_inoutvlimit();
-  const ::NavMessage::SpeedLimit& inoutvlimit() const;
-  ::NavMessage::SpeedLimit* release_inoutvlimit();
-  ::NavMessage::SpeedLimit* mutable_inoutvlimit();
-  void set_allocated_inoutvlimit(::NavMessage::SpeedLimit* inoutvlimit);
-  private:
-  const ::NavMessage::SpeedLimit& _internal_inoutvlimit() const;
-  ::NavMessage::SpeedLimit* _internal_mutable_inoutvlimit();
-  public:
-  void unsafe_arena_set_allocated_inoutvlimit(
-      ::NavMessage::SpeedLimit* inoutvlimit);
-  ::NavMessage::SpeedLimit* unsafe_arena_release_inoutvlimit();
-
-  // .NavMessage.SpeedLimit NodeVelocityLimit = 7;
-  bool has_nodevelocitylimit() const;
-  private:
-  bool _internal_has_nodevelocitylimit() const;
-  public:
-  void clear_nodevelocitylimit();
-  const ::NavMessage::SpeedLimit& nodevelocitylimit() const;
-  ::NavMessage::SpeedLimit* release_nodevelocitylimit();
-  ::NavMessage::SpeedLimit* mutable_nodevelocitylimit();
-  void set_allocated_nodevelocitylimit(::NavMessage::SpeedLimit* nodevelocitylimit);
-  private:
-  const ::NavMessage::SpeedLimit& _internal_nodevelocitylimit() const;
-  ::NavMessage::SpeedLimit* _internal_mutable_nodevelocitylimit();
-  public:
-  void unsafe_arena_set_allocated_nodevelocitylimit(
-      ::NavMessage::SpeedLimit* nodevelocitylimit);
-  ::NavMessage::SpeedLimit* unsafe_arena_release_nodevelocitylimit();
-
-  // .NavMessage.SpeedLimit NodeAngularLimit = 8;
-  bool has_nodeangularlimit() const;
-  private:
-  bool _internal_has_nodeangularlimit() const;
-  public:
-  void clear_nodeangularlimit();
-  const ::NavMessage::SpeedLimit& nodeangularlimit() const;
-  ::NavMessage::SpeedLimit* release_nodeangularlimit();
-  ::NavMessage::SpeedLimit* mutable_nodeangularlimit();
-  void set_allocated_nodeangularlimit(::NavMessage::SpeedLimit* nodeangularlimit);
-  private:
-  const ::NavMessage::SpeedLimit& _internal_nodeangularlimit() const;
-  ::NavMessage::SpeedLimit* _internal_mutable_nodeangularlimit();
-  public:
-  void unsafe_arena_set_allocated_nodeangularlimit(
-      ::NavMessage::SpeedLimit* nodeangularlimit);
-  ::NavMessage::SpeedLimit* unsafe_arena_release_nodeangularlimit();
-
-  // .NavMessage.SpeedLimit adjustVelocitylimit = 9;
-  bool has_adjustvelocitylimit() const;
-  private:
-  bool _internal_has_adjustvelocitylimit() const;
-  public:
-  void clear_adjustvelocitylimit();
-  const ::NavMessage::SpeedLimit& adjustvelocitylimit() const;
-  ::NavMessage::SpeedLimit* release_adjustvelocitylimit();
-  ::NavMessage::SpeedLimit* mutable_adjustvelocitylimit();
-  void set_allocated_adjustvelocitylimit(::NavMessage::SpeedLimit* adjustvelocitylimit);
-  private:
-  const ::NavMessage::SpeedLimit& _internal_adjustvelocitylimit() const;
-  ::NavMessage::SpeedLimit* _internal_mutable_adjustvelocitylimit();
-  public:
-  void unsafe_arena_set_allocated_adjustvelocitylimit(
-      ::NavMessage::SpeedLimit* adjustvelocitylimit);
-  ::NavMessage::SpeedLimit* unsafe_arena_release_adjustvelocitylimit();
-
-  // .NavMessage.SpeedLimit adjustHorizonLimit = 10;
-  bool has_adjusthorizonlimit() const;
-  private:
-  bool _internal_has_adjusthorizonlimit() const;
-  public:
-  void clear_adjusthorizonlimit();
-  const ::NavMessage::SpeedLimit& adjusthorizonlimit() const;
-  ::NavMessage::SpeedLimit* release_adjusthorizonlimit();
-  ::NavMessage::SpeedLimit* mutable_adjusthorizonlimit();
-  void set_allocated_adjusthorizonlimit(::NavMessage::SpeedLimit* adjusthorizonlimit);
-  private:
-  const ::NavMessage::SpeedLimit& _internal_adjusthorizonlimit() const;
-  ::NavMessage::SpeedLimit* _internal_mutable_adjusthorizonlimit();
-  public:
-  void unsafe_arena_set_allocated_adjusthorizonlimit(
-      ::NavMessage::SpeedLimit* adjusthorizonlimit);
-  ::NavMessage::SpeedLimit* unsafe_arena_release_adjusthorizonlimit();
-
   // int32 type = 1;
   void clear_type();
   ::PROTOBUF_NAMESPACE_ID::int32 type() const;
@@ -1609,7 +1362,7 @@ class NewAction PROTOBUF_FINAL :
   void _internal_set_type(::PROTOBUF_NAMESPACE_ID::int32 value);
   public:
 
-  // float wheelbase = 11;
+  // float wheelbase = 6;
   void clear_wheelbase();
   float wheelbase() const;
   void set_wheelbase(float value);
@@ -1618,7 +1371,7 @@ class NewAction PROTOBUF_FINAL :
   void _internal_set_wheelbase(float value);
   public:
 
-  // int32 changedMode = 12;
+  // int32 changedMode = 7;
   void clear_changedmode();
   ::PROTOBUF_NAMESPACE_ID::int32 changedmode() const;
   void set_changedmode(::PROTOBUF_NAMESPACE_ID::int32 value);
@@ -1638,11 +1391,6 @@ class NewAction PROTOBUF_FINAL :
   ::NavMessage::PathNode* spacenode_;
   ::NavMessage::PathNode* passnode_;
   ::NavMessage::PathNode* streetnode_;
-  ::NavMessage::SpeedLimit* inoutvlimit_;
-  ::NavMessage::SpeedLimit* nodevelocitylimit_;
-  ::NavMessage::SpeedLimit* nodeangularlimit_;
-  ::NavMessage::SpeedLimit* adjustvelocitylimit_;
-  ::NavMessage::SpeedLimit* adjusthorizonlimit_;
   ::PROTOBUF_NAMESPACE_ID::int32 type_;
   float wheelbase_;
   ::PROTOBUF_NAMESPACE_ID::int32 changedmode_;
@@ -1693,7 +1441,7 @@ class NavCmd PROTOBUF_FINAL :
                &_NavCmd_default_instance_);
   }
   static constexpr int kIndexInFileMessages =
-    8;
+    7;
 
   friend void swap(NavCmd& a, NavCmd& b) {
     a.Swap(&b);
@@ -1868,7 +1616,7 @@ class NavStatu PROTOBUF_FINAL :
                &_NavStatu_default_instance_);
   }
   static constexpr int kIndexInFileMessages =
-    9;
+    8;
 
   friend void swap(NavStatu& a, NavStatu& b) {
     a.Swap(&b);
@@ -2134,7 +1882,7 @@ class RobotStatu PROTOBUF_FINAL :
                &_RobotStatu_default_instance_);
   }
   static constexpr int kIndexInFileMessages =
-    10;
+    9;
 
   friend void swap(RobotStatu& a, RobotStatu& b) {
     a.Swap(&b);
@@ -2610,50 +2358,6 @@ inline void ToAgvCmd::set_end(::PROTOBUF_NAMESPACE_ID::int32 value) {
 
 // -------------------------------------------------------------------
 
-// SpeedLimit
-
-// float min = 1;
-inline void SpeedLimit::clear_min() {
-  min_ = 0;
-}
-inline float SpeedLimit::_internal_min() const {
-  return min_;
-}
-inline float SpeedLimit::min() const {
-  // @@protoc_insertion_point(field_get:NavMessage.SpeedLimit.min)
-  return _internal_min();
-}
-inline void SpeedLimit::_internal_set_min(float value) {
-  
-  min_ = value;
-}
-inline void SpeedLimit::set_min(float value) {
-  _internal_set_min(value);
-  // @@protoc_insertion_point(field_set:NavMessage.SpeedLimit.min)
-}
-
-// float max = 2;
-inline void SpeedLimit::clear_max() {
-  max_ = 0;
-}
-inline float SpeedLimit::_internal_max() const {
-  return max_;
-}
-inline float SpeedLimit::max() const {
-  // @@protoc_insertion_point(field_get:NavMessage.SpeedLimit.max)
-  return _internal_max();
-}
-inline void SpeedLimit::_internal_set_max(float value) {
-  
-  max_ = value;
-}
-inline void SpeedLimit::set_max(float value) {
-  _internal_set_max(value);
-  // @@protoc_insertion_point(field_set:NavMessage.SpeedLimit.max)
-}
-
-// -------------------------------------------------------------------
-
 // Pose2d
 
 // float x = 1;
@@ -3237,422 +2941,7 @@ NewAction::pathnodes() const {
   return pathnodes_;
 }
 
-// .NavMessage.SpeedLimit InOutVLimit = 6;
-inline bool NewAction::_internal_has_inoutvlimit() const {
-  return this != internal_default_instance() && inoutvlimit_ != nullptr;
-}
-inline bool NewAction::has_inoutvlimit() const {
-  return _internal_has_inoutvlimit();
-}
-inline void NewAction::clear_inoutvlimit() {
-  if (GetArena() == nullptr && inoutvlimit_ != nullptr) {
-    delete inoutvlimit_;
-  }
-  inoutvlimit_ = nullptr;
-}
-inline const ::NavMessage::SpeedLimit& NewAction::_internal_inoutvlimit() const {
-  const ::NavMessage::SpeedLimit* p = inoutvlimit_;
-  return p != nullptr ? *p : *reinterpret_cast<const ::NavMessage::SpeedLimit*>(
-      &::NavMessage::_SpeedLimit_default_instance_);
-}
-inline const ::NavMessage::SpeedLimit& NewAction::inoutvlimit() const {
-  // @@protoc_insertion_point(field_get:NavMessage.NewAction.InOutVLimit)
-  return _internal_inoutvlimit();
-}
-inline void NewAction::unsafe_arena_set_allocated_inoutvlimit(
-    ::NavMessage::SpeedLimit* inoutvlimit) {
-  if (GetArena() == nullptr) {
-    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(inoutvlimit_);
-  }
-  inoutvlimit_ = inoutvlimit;
-  if (inoutvlimit) {
-    
-  } else {
-    
-  }
-  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavMessage.NewAction.InOutVLimit)
-}
-inline ::NavMessage::SpeedLimit* NewAction::release_inoutvlimit() {
-  
-  ::NavMessage::SpeedLimit* temp = inoutvlimit_;
-  inoutvlimit_ = nullptr;
-  if (GetArena() != nullptr) {
-    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
-  }
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::unsafe_arena_release_inoutvlimit() {
-  // @@protoc_insertion_point(field_release:NavMessage.NewAction.InOutVLimit)
-  
-  ::NavMessage::SpeedLimit* temp = inoutvlimit_;
-  inoutvlimit_ = nullptr;
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::_internal_mutable_inoutvlimit() {
-  
-  if (inoutvlimit_ == nullptr) {
-    auto* p = CreateMaybeMessage<::NavMessage::SpeedLimit>(GetArena());
-    inoutvlimit_ = p;
-  }
-  return inoutvlimit_;
-}
-inline ::NavMessage::SpeedLimit* NewAction::mutable_inoutvlimit() {
-  // @@protoc_insertion_point(field_mutable:NavMessage.NewAction.InOutVLimit)
-  return _internal_mutable_inoutvlimit();
-}
-inline void NewAction::set_allocated_inoutvlimit(::NavMessage::SpeedLimit* inoutvlimit) {
-  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
-  if (message_arena == nullptr) {
-    delete inoutvlimit_;
-  }
-  if (inoutvlimit) {
-    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
-      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(inoutvlimit);
-    if (message_arena != submessage_arena) {
-      inoutvlimit = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
-          message_arena, inoutvlimit, submessage_arena);
-    }
-    
-  } else {
-    
-  }
-  inoutvlimit_ = inoutvlimit;
-  // @@protoc_insertion_point(field_set_allocated:NavMessage.NewAction.InOutVLimit)
-}
-
-// .NavMessage.SpeedLimit NodeVelocityLimit = 7;
-inline bool NewAction::_internal_has_nodevelocitylimit() const {
-  return this != internal_default_instance() && nodevelocitylimit_ != nullptr;
-}
-inline bool NewAction::has_nodevelocitylimit() const {
-  return _internal_has_nodevelocitylimit();
-}
-inline void NewAction::clear_nodevelocitylimit() {
-  if (GetArena() == nullptr && nodevelocitylimit_ != nullptr) {
-    delete nodevelocitylimit_;
-  }
-  nodevelocitylimit_ = nullptr;
-}
-inline const ::NavMessage::SpeedLimit& NewAction::_internal_nodevelocitylimit() const {
-  const ::NavMessage::SpeedLimit* p = nodevelocitylimit_;
-  return p != nullptr ? *p : *reinterpret_cast<const ::NavMessage::SpeedLimit*>(
-      &::NavMessage::_SpeedLimit_default_instance_);
-}
-inline const ::NavMessage::SpeedLimit& NewAction::nodevelocitylimit() const {
-  // @@protoc_insertion_point(field_get:NavMessage.NewAction.NodeVelocityLimit)
-  return _internal_nodevelocitylimit();
-}
-inline void NewAction::unsafe_arena_set_allocated_nodevelocitylimit(
-    ::NavMessage::SpeedLimit* nodevelocitylimit) {
-  if (GetArena() == nullptr) {
-    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(nodevelocitylimit_);
-  }
-  nodevelocitylimit_ = nodevelocitylimit;
-  if (nodevelocitylimit) {
-    
-  } else {
-    
-  }
-  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavMessage.NewAction.NodeVelocityLimit)
-}
-inline ::NavMessage::SpeedLimit* NewAction::release_nodevelocitylimit() {
-  
-  ::NavMessage::SpeedLimit* temp = nodevelocitylimit_;
-  nodevelocitylimit_ = nullptr;
-  if (GetArena() != nullptr) {
-    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
-  }
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::unsafe_arena_release_nodevelocitylimit() {
-  // @@protoc_insertion_point(field_release:NavMessage.NewAction.NodeVelocityLimit)
-  
-  ::NavMessage::SpeedLimit* temp = nodevelocitylimit_;
-  nodevelocitylimit_ = nullptr;
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::_internal_mutable_nodevelocitylimit() {
-  
-  if (nodevelocitylimit_ == nullptr) {
-    auto* p = CreateMaybeMessage<::NavMessage::SpeedLimit>(GetArena());
-    nodevelocitylimit_ = p;
-  }
-  return nodevelocitylimit_;
-}
-inline ::NavMessage::SpeedLimit* NewAction::mutable_nodevelocitylimit() {
-  // @@protoc_insertion_point(field_mutable:NavMessage.NewAction.NodeVelocityLimit)
-  return _internal_mutable_nodevelocitylimit();
-}
-inline void NewAction::set_allocated_nodevelocitylimit(::NavMessage::SpeedLimit* nodevelocitylimit) {
-  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
-  if (message_arena == nullptr) {
-    delete nodevelocitylimit_;
-  }
-  if (nodevelocitylimit) {
-    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
-      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(nodevelocitylimit);
-    if (message_arena != submessage_arena) {
-      nodevelocitylimit = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
-          message_arena, nodevelocitylimit, submessage_arena);
-    }
-    
-  } else {
-    
-  }
-  nodevelocitylimit_ = nodevelocitylimit;
-  // @@protoc_insertion_point(field_set_allocated:NavMessage.NewAction.NodeVelocityLimit)
-}
-
-// .NavMessage.SpeedLimit NodeAngularLimit = 8;
-inline bool NewAction::_internal_has_nodeangularlimit() const {
-  return this != internal_default_instance() && nodeangularlimit_ != nullptr;
-}
-inline bool NewAction::has_nodeangularlimit() const {
-  return _internal_has_nodeangularlimit();
-}
-inline void NewAction::clear_nodeangularlimit() {
-  if (GetArena() == nullptr && nodeangularlimit_ != nullptr) {
-    delete nodeangularlimit_;
-  }
-  nodeangularlimit_ = nullptr;
-}
-inline const ::NavMessage::SpeedLimit& NewAction::_internal_nodeangularlimit() const {
-  const ::NavMessage::SpeedLimit* p = nodeangularlimit_;
-  return p != nullptr ? *p : *reinterpret_cast<const ::NavMessage::SpeedLimit*>(
-      &::NavMessage::_SpeedLimit_default_instance_);
-}
-inline const ::NavMessage::SpeedLimit& NewAction::nodeangularlimit() const {
-  // @@protoc_insertion_point(field_get:NavMessage.NewAction.NodeAngularLimit)
-  return _internal_nodeangularlimit();
-}
-inline void NewAction::unsafe_arena_set_allocated_nodeangularlimit(
-    ::NavMessage::SpeedLimit* nodeangularlimit) {
-  if (GetArena() == nullptr) {
-    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(nodeangularlimit_);
-  }
-  nodeangularlimit_ = nodeangularlimit;
-  if (nodeangularlimit) {
-    
-  } else {
-    
-  }
-  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavMessage.NewAction.NodeAngularLimit)
-}
-inline ::NavMessage::SpeedLimit* NewAction::release_nodeangularlimit() {
-  
-  ::NavMessage::SpeedLimit* temp = nodeangularlimit_;
-  nodeangularlimit_ = nullptr;
-  if (GetArena() != nullptr) {
-    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
-  }
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::unsafe_arena_release_nodeangularlimit() {
-  // @@protoc_insertion_point(field_release:NavMessage.NewAction.NodeAngularLimit)
-  
-  ::NavMessage::SpeedLimit* temp = nodeangularlimit_;
-  nodeangularlimit_ = nullptr;
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::_internal_mutable_nodeangularlimit() {
-  
-  if (nodeangularlimit_ == nullptr) {
-    auto* p = CreateMaybeMessage<::NavMessage::SpeedLimit>(GetArena());
-    nodeangularlimit_ = p;
-  }
-  return nodeangularlimit_;
-}
-inline ::NavMessage::SpeedLimit* NewAction::mutable_nodeangularlimit() {
-  // @@protoc_insertion_point(field_mutable:NavMessage.NewAction.NodeAngularLimit)
-  return _internal_mutable_nodeangularlimit();
-}
-inline void NewAction::set_allocated_nodeangularlimit(::NavMessage::SpeedLimit* nodeangularlimit) {
-  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
-  if (message_arena == nullptr) {
-    delete nodeangularlimit_;
-  }
-  if (nodeangularlimit) {
-    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
-      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(nodeangularlimit);
-    if (message_arena != submessage_arena) {
-      nodeangularlimit = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
-          message_arena, nodeangularlimit, submessage_arena);
-    }
-    
-  } else {
-    
-  }
-  nodeangularlimit_ = nodeangularlimit;
-  // @@protoc_insertion_point(field_set_allocated:NavMessage.NewAction.NodeAngularLimit)
-}
-
-// .NavMessage.SpeedLimit adjustVelocitylimit = 9;
-inline bool NewAction::_internal_has_adjustvelocitylimit() const {
-  return this != internal_default_instance() && adjustvelocitylimit_ != nullptr;
-}
-inline bool NewAction::has_adjustvelocitylimit() const {
-  return _internal_has_adjustvelocitylimit();
-}
-inline void NewAction::clear_adjustvelocitylimit() {
-  if (GetArena() == nullptr && adjustvelocitylimit_ != nullptr) {
-    delete adjustvelocitylimit_;
-  }
-  adjustvelocitylimit_ = nullptr;
-}
-inline const ::NavMessage::SpeedLimit& NewAction::_internal_adjustvelocitylimit() const {
-  const ::NavMessage::SpeedLimit* p = adjustvelocitylimit_;
-  return p != nullptr ? *p : *reinterpret_cast<const ::NavMessage::SpeedLimit*>(
-      &::NavMessage::_SpeedLimit_default_instance_);
-}
-inline const ::NavMessage::SpeedLimit& NewAction::adjustvelocitylimit() const {
-  // @@protoc_insertion_point(field_get:NavMessage.NewAction.adjustVelocitylimit)
-  return _internal_adjustvelocitylimit();
-}
-inline void NewAction::unsafe_arena_set_allocated_adjustvelocitylimit(
-    ::NavMessage::SpeedLimit* adjustvelocitylimit) {
-  if (GetArena() == nullptr) {
-    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(adjustvelocitylimit_);
-  }
-  adjustvelocitylimit_ = adjustvelocitylimit;
-  if (adjustvelocitylimit) {
-    
-  } else {
-    
-  }
-  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavMessage.NewAction.adjustVelocitylimit)
-}
-inline ::NavMessage::SpeedLimit* NewAction::release_adjustvelocitylimit() {
-  
-  ::NavMessage::SpeedLimit* temp = adjustvelocitylimit_;
-  adjustvelocitylimit_ = nullptr;
-  if (GetArena() != nullptr) {
-    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
-  }
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::unsafe_arena_release_adjustvelocitylimit() {
-  // @@protoc_insertion_point(field_release:NavMessage.NewAction.adjustVelocitylimit)
-  
-  ::NavMessage::SpeedLimit* temp = adjustvelocitylimit_;
-  adjustvelocitylimit_ = nullptr;
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::_internal_mutable_adjustvelocitylimit() {
-  
-  if (adjustvelocitylimit_ == nullptr) {
-    auto* p = CreateMaybeMessage<::NavMessage::SpeedLimit>(GetArena());
-    adjustvelocitylimit_ = p;
-  }
-  return adjustvelocitylimit_;
-}
-inline ::NavMessage::SpeedLimit* NewAction::mutable_adjustvelocitylimit() {
-  // @@protoc_insertion_point(field_mutable:NavMessage.NewAction.adjustVelocitylimit)
-  return _internal_mutable_adjustvelocitylimit();
-}
-inline void NewAction::set_allocated_adjustvelocitylimit(::NavMessage::SpeedLimit* adjustvelocitylimit) {
-  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
-  if (message_arena == nullptr) {
-    delete adjustvelocitylimit_;
-  }
-  if (adjustvelocitylimit) {
-    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
-      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(adjustvelocitylimit);
-    if (message_arena != submessage_arena) {
-      adjustvelocitylimit = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
-          message_arena, adjustvelocitylimit, submessage_arena);
-    }
-    
-  } else {
-    
-  }
-  adjustvelocitylimit_ = adjustvelocitylimit;
-  // @@protoc_insertion_point(field_set_allocated:NavMessage.NewAction.adjustVelocitylimit)
-}
-
-// .NavMessage.SpeedLimit adjustHorizonLimit = 10;
-inline bool NewAction::_internal_has_adjusthorizonlimit() const {
-  return this != internal_default_instance() && adjusthorizonlimit_ != nullptr;
-}
-inline bool NewAction::has_adjusthorizonlimit() const {
-  return _internal_has_adjusthorizonlimit();
-}
-inline void NewAction::clear_adjusthorizonlimit() {
-  if (GetArena() == nullptr && adjusthorizonlimit_ != nullptr) {
-    delete adjusthorizonlimit_;
-  }
-  adjusthorizonlimit_ = nullptr;
-}
-inline const ::NavMessage::SpeedLimit& NewAction::_internal_adjusthorizonlimit() const {
-  const ::NavMessage::SpeedLimit* p = adjusthorizonlimit_;
-  return p != nullptr ? *p : *reinterpret_cast<const ::NavMessage::SpeedLimit*>(
-      &::NavMessage::_SpeedLimit_default_instance_);
-}
-inline const ::NavMessage::SpeedLimit& NewAction::adjusthorizonlimit() const {
-  // @@protoc_insertion_point(field_get:NavMessage.NewAction.adjustHorizonLimit)
-  return _internal_adjusthorizonlimit();
-}
-inline void NewAction::unsafe_arena_set_allocated_adjusthorizonlimit(
-    ::NavMessage::SpeedLimit* adjusthorizonlimit) {
-  if (GetArena() == nullptr) {
-    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(adjusthorizonlimit_);
-  }
-  adjusthorizonlimit_ = adjusthorizonlimit;
-  if (adjusthorizonlimit) {
-    
-  } else {
-    
-  }
-  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavMessage.NewAction.adjustHorizonLimit)
-}
-inline ::NavMessage::SpeedLimit* NewAction::release_adjusthorizonlimit() {
-  
-  ::NavMessage::SpeedLimit* temp = adjusthorizonlimit_;
-  adjusthorizonlimit_ = nullptr;
-  if (GetArena() != nullptr) {
-    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
-  }
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::unsafe_arena_release_adjusthorizonlimit() {
-  // @@protoc_insertion_point(field_release:NavMessage.NewAction.adjustHorizonLimit)
-  
-  ::NavMessage::SpeedLimit* temp = adjusthorizonlimit_;
-  adjusthorizonlimit_ = nullptr;
-  return temp;
-}
-inline ::NavMessage::SpeedLimit* NewAction::_internal_mutable_adjusthorizonlimit() {
-  
-  if (adjusthorizonlimit_ == nullptr) {
-    auto* p = CreateMaybeMessage<::NavMessage::SpeedLimit>(GetArena());
-    adjusthorizonlimit_ = p;
-  }
-  return adjusthorizonlimit_;
-}
-inline ::NavMessage::SpeedLimit* NewAction::mutable_adjusthorizonlimit() {
-  // @@protoc_insertion_point(field_mutable:NavMessage.NewAction.adjustHorizonLimit)
-  return _internal_mutable_adjusthorizonlimit();
-}
-inline void NewAction::set_allocated_adjusthorizonlimit(::NavMessage::SpeedLimit* adjusthorizonlimit) {
-  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
-  if (message_arena == nullptr) {
-    delete adjusthorizonlimit_;
-  }
-  if (adjusthorizonlimit) {
-    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
-      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(adjusthorizonlimit);
-    if (message_arena != submessage_arena) {
-      adjusthorizonlimit = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
-          message_arena, adjusthorizonlimit, submessage_arena);
-    }
-    
-  } else {
-    
-  }
-  adjusthorizonlimit_ = adjusthorizonlimit;
-  // @@protoc_insertion_point(field_set_allocated:NavMessage.NewAction.adjustHorizonLimit)
-}
-
-// float wheelbase = 11;
+// float wheelbase = 6;
 inline void NewAction::clear_wheelbase() {
   wheelbase_ = 0;
 }
@@ -3672,7 +2961,7 @@ inline void NewAction::set_wheelbase(float value) {
   // @@protoc_insertion_point(field_set:NavMessage.NewAction.wheelbase)
 }
 
-// int32 changedMode = 12;
+// int32 changedMode = 7;
 inline void NewAction::clear_changedmode() {
   changedmode_ = 0;
 }
@@ -4442,8 +3731,6 @@ inline void RobotStatu::set_allocated_agvstatu(::NavMessage::AgvStatu* agvstatu)
 
 // -------------------------------------------------------------------
 
-// -------------------------------------------------------------------
-
 
 // @@protoc_insertion_point(namespace_scope)
 

+ 109 - 25
MPC/navigation.cpp

@@ -52,7 +52,7 @@ double limit(double x,double min,double max){
 
 }
 
-double next_speed(double speed,double target_speed,double acc,double dt=0.1)
+double next_speed(double speed,double target_speed,double acc,double dt)
 {
   if(fabs(target_speed-speed)/dt<acc)
   {
@@ -336,7 +336,7 @@ bool Navigation::Stop() {
 
 bool Navigation::SlowlyStop() {
 
-  double acc = 5.0;
+  double acc = 3.0;
   double dt = 0.1;
   while (cancel_ == false) {
     if (timedV_.timeout() == false) {
@@ -566,20 +566,30 @@ bool Navigation::execute_nodes(NavMessage::NewAction action)
 {
   if(action.type()==3 || action.type()==4) //最优动作导航 or 导航中保证朝向严格一致
   {
-    if(!action.has_nodevelocitylimit() || !action.has_nodeangularlimit()||
-        !action.has_adjustvelocitylimit()|| !action.has_adjusthorizonlimit()
-        || action.pathnodes_size()==0) {
+    if(!parameter_.has_nodeangularlimit()|| !parameter_.has_nodevelocitylimit()||action.pathnodes_size()==0) {
       std::cout << "execute pathNodes failed ,Action invalid:" << action.DebugString() << std::endl;
       return false;
     }
     bool anyDirect=(action.type()==3);
 
     //速度限制
-    stLimit adjust_angular={ action.nodeangularlimit().min(),action.nodeangularlimit().max() };
-    stLimit mpc_velocity={ action.nodevelocitylimit().min(),action.nodevelocitylimit().max() };
+    stLimit adjust_angular={ parameter_.nodeangularlimit().min(),parameter_.nodeangularlimit().max() };
+    stLimit mpc_velocity={ parameter_.nodevelocitylimit().min(),parameter_.nodevelocitylimit().max() };
 
     for(int i=0;i< action.pathnodes_size();++i) {
       NavMessage::PathNode node = action.pathnodes(i);
+      if(i+1<action.pathnodes_size()){
+        NavMessage::PathNode next = action.pathnodes(i+1);
+        Pose2d vec(next.x()-node.x(),next.y()-node.y(),0);
+        node.set_theta(Pose2d::vector2yaw(vec.x(),vec.y()));
+        node.set_l(0.3);
+        node.set_w(0.1);
+
+      }else{
+        node.set_theta(0);
+        node.set_w(0.2);
+        node.set_l(0.2);
+      }
       if(MoveToTarget(node,mpc_velocity,adjust_angular,anyDirect,true)==false)
         return false;
       else
@@ -591,12 +601,76 @@ bool Navigation::execute_nodes(NavMessage::NewAction action)
   return false;
 }
 
+bool Navigation::RotateBeforeEnterSpace(NavMessage::PathNode space,double wheelbase,NavMessage::PathNode& target) {
+  if (timedBrotherNavStatu_.timeout() || timedPose_.timeout()) {
+    printf(" rotate failed : timedBrotherNavStatu_ or pose timeout\n");
+    return false;
+  }
+  NavMessage::NavStatu brother = timedBrotherNavStatu_.Get();
+
+  stLimit limit_rotate = {2 * M_PI / 180.0, 15 * M_PI / 180.0};
+  double acc_angular = 20 * M_PI / 180.0;
+  double dt = 0.1;
+  Pose2d rotated = timedPose_.Get();
+
+  //前车先到,当前车进入2点,保持与前车一致的朝向
+  if (brother.in_space() && brother.space_id() == space.id()) {
+    rotated.mutable_theta() = brother.odom().theta();
+  } else { //当前车先到(后车),倒车入库
+    rotated.mutable_theta() = space.theta();
+    rotated = rotated.rotate(rotated.x(), rotated.y(), M_PI);
+  }
+  double x = space.x() - wheelbase/2 * cos(rotated.theta());
+  double y = space.y() - wheelbase/2 * sin(rotated.theta());
+  target.set_x(x);
+  target.set_y(y);
+  target.set_theta(rotated.theta());
+  target.set_l(0.05);
+  target.set_w(0.03);
+  target.set_id(space.id());
+
+  //整车协调的时候,保持前后与车位一致即可
+  if(move_mode_==Monitor_emqx::eMain){
+    double yawDiff1 = (rotated - timedPose_.Get()).theta();
+    double yawDiff2 = (rotated+Pose2d(0,0,M_PI) - timedPose_.Get()).theta();
+    if(fabs(yawDiff1)<fabs(yawDiff2)){
+      rotated=rotated+Pose2d(0,0,M_PI);
+    }
+  }
+
+  while (cancel_ == false) {
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    Pose2d current = timedPose_.Get();
+    double yawDiff = (rotated - current).theta();
+    if (fabs(yawDiff) > 1 * M_PI / 180.0) {
+      double theta = limit_gause(yawDiff, limit_rotate.min, limit_rotate.max);
+      double angular = next_speed(timedA_.Get(), theta, acc_angular, dt);
+      double limit_angular = limit(angular, limit_rotate.min, limit_rotate.max);
+
+      SendMoveCmd(move_mode_, Monitor_emqx::eRotate, 0, limit_angular);
+      actionType_ = eRotation;
+      printf(" RotateBeforeEnterSpace | input anguar:%f,next angular:%f,down:%f diff:%f anyDirect:false\n",
+             timedA_.Get(), angular, limit_angular, yawDiff);
+
+      continue;
+    } else {
+      if (fabs(timedA_.Get()) < 5 * M_PI / 180.0) {
+        printf(" RotateBeforeEnterSpace refer target completed\n");
+        printf("---------------- update new target :%f %f %f \n",target.x(),target.y(),target.theta());
+        return true;
+      }
+    }
+  }
+  return false;
+
+}
+
 bool Navigation::execute_InOut_space(NavMessage::NewAction action) {
   if (action.type() != 1 && action.type() != 2) {
     printf(" Inout_space failed : msg action type must ==1\n ");
     return false;
   }
-  if (!action.has_inoutvlimit() || !action.has_spacenode() ||
+  if (!parameter_.has_inoutvlimit() || !action.has_spacenode() ||
       !action.has_streetnode()) {
     std::cout << "execute enter_space failed ,Action miss some infos:" << action.DebugString() << std::endl;
     return false;
@@ -606,10 +680,14 @@ bool Navigation::execute_InOut_space(NavMessage::NewAction action) {
     return false;
   }
 
-  stLimit limit_v={action.inoutvlimit().min(),action.inoutvlimit().max()};
-  stLimit limit_w={2*M_PI/180.0,10*M_PI/180.0};
+  stLimit limit_v={parameter_.inoutvlimit().min(),parameter_.inoutvlimit().max()};
+  stLimit limit_w={2*M_PI/180.0,20*M_PI/180.0};
   //入库,起点为streetNode
   if(action.type()==1){
+    Pose2d vec(action.spacenode().x()-action.streetnode().x(),action.spacenode().y()-action.streetnode().y(),0);
+    action.mutable_streetnode()->set_l(0.2);
+    action.mutable_streetnode()->set_w(0.05);
+    action.mutable_streetnode()->set_theta(Pose2d::vector2yaw(vec.x(),vec.y()));
     if(MoveToTarget(action.streetnode(),limit_v,limit_w,true,true)==false)
     {
       printf(" Enter space failed type:%d: MoveTo StreetNode failed\n", action.type());
@@ -617,30 +695,33 @@ bool Navigation::execute_InOut_space(NavMessage::NewAction action) {
     }
     //移动到库位点, 禁止任意方向// 不允许巡线中停下旋转(当无法到达目标点时,返回false)
     printf("inout ----------------------------------------\n");
+    //计算车位朝向
+    action.mutable_spacenode()->set_theta(Pose2d::vector2yaw(vec.x(),vec.y()));
     //计算当前车是进入车位1点还是2点
-    /*if(timedBrotherNavStatu_.timeout()){
-      printf("Enter to space failed,timedBrotherNavStatu_ timeout\n");
+    NavMessage::PathNode new_atrget;
+    if(RotateBeforeEnterSpace(action.spacenode(),action.wheelbase(),new_atrget)==false){
       return false;
     }
-    if(timedBrotherNavStatu_.Get().in_space()){
-
-    }*/
-    if(MoveToTarget(action.spacenode(),limit_v,limit_w,false,false)==false)
+    if(MoveToTarget(new_atrget,limit_v,limit_w,true,false)==false)
     {
       printf(" Enter space failed type:%d: MoveTo StreetNode failed\n", action.type());
       return false;
     }
   }else if(action.type()==2){
     Pose2d space(action.spacenode().x(),action.spacenode().y(),0);
-    Pose2d diff=Pose2d::relativePose(space,timedPose_.Get());
-    if(Pose2d::abs(diff)<Pose2d(0.03,0.1,2*M_PI)){
+    Pose2d diff=Pose2d::abs(Pose2d::relativePose(space,timedPose_.Get()));
+    if(diff.y()<0.05){
       //出库,移动到马路点,允许自由方向,不允许中途旋转
+      Pose2d vec(action.streetnode().x()-action.spacenode().x(),action.streetnode().y()-action.spacenode().y(),0);
+      action.mutable_streetnode()->set_theta(Pose2d::vector2yaw(vec.x(),vec.y()));
+      action.mutable_streetnode()->set_l(0.2);
+      action.mutable_streetnode()->set_w(0.1);
       if(MoveToTarget(action.streetnode(),limit_v,limit_w,true,false)==false){
-        printf(" Enter space failed type:%d: MoveTo StreetNode failed\n", action.type());
+        printf(" out space failed type:%d: MoveTo StreetNode failed\n", action.type());
         return false;
       }
     }else{
-      std::cout<<" Out space failed: current pose too far from space node:"<<space<<std::endl;
+      std::cout<<" Out space failed: current pose too far from space node:"<<space<<",diff:"<<diff<<std::endl;
       return false;
     }
 
@@ -734,10 +815,10 @@ bool Navigation::IsArrived(NavMessage::PathNode targetNode)
   double ty=targetNode.y();
   double l=fabs(targetNode.l());
   double w=fabs(targetNode.w());
-  double theta=targetNode.theta();
+  double theta=-targetNode.theta();
 
   if(l<1e-10 || w<1e-10){
-    printf("IsArrived: Error target l/w ==0\n");
+    printf("IsArrived: Error target l or w == 0\n");
     return false;
   }
 
@@ -921,12 +1002,15 @@ bool Navigation::PossibleToTarget(NavMessage::PathNode targetNode,bool directY)
   double ty = targetNode.y();
   double l = fabs(targetNode.l());
   double w = fabs(targetNode.w());
-  double theta = targetNode.theta();
+  double theta = -targetNode.theta();
 
   double W = 2.45;
   double L = 1.3;
+  double minYaw=5*M_PI/180.0;
   if(move_mode_==Monitor_emqx::eMain){
     L=1.3+2.7;
+    if(directY)
+      minYaw=2*M_PI/180.0;
   }
   if(directY){
     current=current.rotate(current.x(),current.y(),M_PI/2);
@@ -934,8 +1018,8 @@ bool Navigation::PossibleToTarget(NavMessage::PathNode targetNode,bool directY)
     W=L;
     L=t;
   }
-  double minR = W / 2 + L / tan(5 * M_PI / 180.0);
-  printf("l:%f,w:%f\n",l,w);
+  double minR = W / 2 + L / tan(minYaw * M_PI / 180.0);
+  //printf("l:%f,w:%f\n",l,w);
   std::vector<Pose2d> poses = Pose2d::generate_rectangle_vertexs(Pose2d(tx, ty, 0), l*2, w*2);
 
   bool nagY=false;

+ 11 - 4
MPC/navigation.h

@@ -111,10 +111,15 @@ public:
      */
     bool execute_nodes(NavMessage::NewAction action);
     /*
-     * 进库
+     * 进
      */
     bool execute_InOut_space(NavMessage::NewAction action);
-
+    /*
+     * 根据自身和配对车辆状态,调整入库姿态,先到的进入车位1点,后车先到的倒车入库,后到的车与先到的车保持朝向一致
+     * space:输入车位点,
+     * target:输出目标点
+     */
+    virtual bool RotateBeforeEnterSpace(NavMessage::PathNode space,double wheelbase,NavMessage::PathNode& target);
 
     virtual bool clamp_close();
     virtual bool clamp_open();
@@ -162,6 +167,7 @@ public:
     bool cancel_=false;
 
     Monitor_emqx::ActionMode move_mode_=Monitor_emqx::eSingle;
+
     bool isInSpace_; //是否在车位或者正在进入车位
     std::string space_id_;
     TimedLockData<Trajectory> selected_traj_;
@@ -170,6 +176,7 @@ public:
     NavParameter::Navigation_parameter parameter_;
     RWheelPosition  RWheel_position_;
 };
-
-
+double limit_gause(double x,double min,double max);
+double limit(double x,double min,double max);
+double next_speed(double speed,double target_speed,double acc,double dt=0.1);
 #endif //LIO_LIVOX_CPP_MPC_NAVIGATION_H_

+ 54 - 0
MPC/navigation_main.cpp

@@ -173,4 +173,58 @@ bool NavigationMain::clamp_open() {
     return false;
   }
   return false;
+}
+
+bool NavigationMain::RotateBeforeEnterSpace(NavMessage::PathNode space,double wheelbase,NavMessage::PathNode& target) {
+  if (timedBrotherNavStatu_.timeout() || timedPose_.timeout()) {
+    printf(" rotate failed : timedBrotherNavStatu_ or pose timeout\n");
+    return false;
+  }
+  NavMessage::NavStatu brother = timedBrotherNavStatu_.Get();
+
+  stLimit limit_rotate = {2 * M_PI / 180.0, 15 * M_PI / 180.0};
+  double acc_angular = 25 * M_PI / 180.0;
+  double dt = 0.1;
+  Pose2d rotated = Pose2d(space.x(),space.y(),space.theta());
+  target.set_l(0.05);
+  target.set_w(0.03);
+  target.set_id(space.id());
+  //后车先到,当前车进入2点,保持与后车一致的朝向
+  if (brother.in_space() && brother.space_id() == space.id()) {
+    rotated.mutable_theta() = brother.odom().theta();
+  } else { //当前车先到,正向
+    rotated.mutable_theta() = space.theta();
+  }
+  std::cout<<"===============================> RotateBeforeEnterSpace ,target:"<<rotated<<std::endl;
+  double x = space.x() + wheelbase/2.0 * cos(rotated.theta());
+  double y = space.y() + wheelbase/2.0 * sin(rotated.theta());
+  target.set_x(x);
+  target.set_y(y);
+  target.set_theta(rotated.theta());
+
+  while (cancel_ == false) {
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    Pose2d current = timedPose_.Get();
+    double yawDiff = (rotated - current).theta();
+    if (fabs(yawDiff) > 1 * M_PI / 180.0) {
+      double theta = limit_gause(yawDiff, limit_rotate.min, limit_rotate.max);
+      double angular = next_speed(timedA_.Get(), theta, acc_angular, dt);
+      double limit_angular = limit(angular, limit_rotate.min, limit_rotate.max);
+
+      SendMoveCmd(move_mode_, Monitor_emqx::eRotate, 0, limit_angular);
+      actionType_ = eRotation;
+      printf(" RotateBeforeEnterSpace | input anguar:%f,next angular:%f,down:%f diff:%f anyDirect:false\n",
+             timedA_.Get(), angular, limit_angular, yawDiff);
+
+      continue;
+    } else {
+      if (fabs(timedA_.Get()) < 5 * M_PI / 180.0) {
+        printf(" RotateBeforeEnterSpace refer target completed\n");
+        printf("---------------- update new target :%f %f %f \n",target.x(),target.y(),target.theta());
+        return true;
+      }
+    }
+  }
+  return false;
+
 }

+ 1 - 0
MPC/navigation_main.h

@@ -49,6 +49,7 @@ public:
 
 
 protected:
+    virtual bool RotateBeforeEnterSpace(NavMessage::PathNode space,double wheelbase,NavMessage::PathNode& target);
     virtual void SendMoveCmd(Monitor_emqx::ActionMode mode,Monitor_emqx::ActionType type,
                              double v,double angular);
     virtual void HandleNavCmd(const NavMessage::NavCmd& cmd);

+ 670 - 17
MPC/parameter.pb.cc

@@ -18,6 +18,7 @@ extern PROTOBUF_INTERNAL_EXPORT_parameter_2eproto ::PROTOBUF_NAMESPACE_ID::inter
 extern PROTOBUF_INTERNAL_EXPORT_parameter_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_BrotherEmqx_parameter_2eproto;
 extern PROTOBUF_INTERNAL_EXPORT_parameter_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_Emqx_parameter_parameter_2eproto;
 extern PROTOBUF_INTERNAL_EXPORT_parameter_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_MPC_parameter_parameter_2eproto;
+extern PROTOBUF_INTERNAL_EXPORT_parameter_2eproto ::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_SpeedLimit_parameter_2eproto;
 namespace NavParameter {
 class AgvEmqx_parameterDefaultTypeInternal {
  public:
@@ -35,11 +36,33 @@ class MPC_parameterDefaultTypeInternal {
  public:
   ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<MPC_parameter> _instance;
 } _MPC_parameter_default_instance_;
+class SpeedLimitDefaultTypeInternal {
+ public:
+  ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<SpeedLimit> _instance;
+} _SpeedLimit_default_instance_;
+class AccuracyDefaultTypeInternal {
+ public:
+  ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<Accuracy> _instance;
+} _Accuracy_default_instance_;
 class Navigation_parameterDefaultTypeInternal {
  public:
   ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<Navigation_parameter> _instance;
 } _Navigation_parameter_default_instance_;
 }  // namespace NavParameter
+static void InitDefaultsscc_info_Accuracy_parameter_2eproto() {
+  GOOGLE_PROTOBUF_VERIFY_VERSION;
+
+  {
+    void* ptr = &::NavParameter::_Accuracy_default_instance_;
+    new (ptr) ::NavParameter::Accuracy();
+    ::PROTOBUF_NAMESPACE_ID::internal::OnShutdownDestroyMessage(ptr);
+  }
+  ::NavParameter::Accuracy::InitAsDefaultInstance();
+}
+
+::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_Accuracy_parameter_2eproto =
+    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 0, 0, InitDefaultsscc_info_Accuracy_parameter_2eproto}, {}};
+
 static void InitDefaultsscc_info_AgvEmqx_parameter_parameter_2eproto() {
   GOOGLE_PROTOBUF_VERIFY_VERSION;
 
@@ -107,14 +130,29 @@ static void InitDefaultsscc_info_Navigation_parameter_parameter_2eproto() {
   ::NavParameter::Navigation_parameter::InitAsDefaultInstance();
 }
 
-::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<4> scc_info_Navigation_parameter_parameter_2eproto =
-    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 4, 0, InitDefaultsscc_info_Navigation_parameter_parameter_2eproto}, {
+::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<5> scc_info_Navigation_parameter_parameter_2eproto =
+    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 5, 0, InitDefaultsscc_info_Navigation_parameter_parameter_2eproto}, {
       &scc_info_AgvEmqx_parameter_parameter_2eproto.base,
       &scc_info_Emqx_parameter_parameter_2eproto.base,
       &scc_info_BrotherEmqx_parameter_2eproto.base,
-      &scc_info_MPC_parameter_parameter_2eproto.base,}};
+      &scc_info_MPC_parameter_parameter_2eproto.base,
+      &scc_info_SpeedLimit_parameter_2eproto.base,}};
 
-static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_parameter_2eproto[5];
+static void InitDefaultsscc_info_SpeedLimit_parameter_2eproto() {
+  GOOGLE_PROTOBUF_VERIFY_VERSION;
+
+  {
+    void* ptr = &::NavParameter::_SpeedLimit_default_instance_;
+    new (ptr) ::NavParameter::SpeedLimit();
+    ::PROTOBUF_NAMESPACE_ID::internal::OnShutdownDestroyMessage(ptr);
+  }
+  ::NavParameter::SpeedLimit::InitAsDefaultInstance();
+}
+
+::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_SpeedLimit_parameter_2eproto =
+    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 0, 0, InitDefaultsscc_info_SpeedLimit_parameter_2eproto}, {}};
+
+static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_parameter_2eproto[7];
 static constexpr ::PROTOBUF_NAMESPACE_ID::EnumDescriptor const** file_level_enum_descriptors_parameter_2eproto = nullptr;
 static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_parameter_2eproto = nullptr;
 
@@ -160,6 +198,20 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_parameter_2eproto::offsets[] P
   PROTOBUF_FIELD_OFFSET(::NavParameter::MPC_parameter, acc_velocity_),
   PROTOBUF_FIELD_OFFSET(::NavParameter::MPC_parameter, acc_angular_),
   ~0u,  // no _has_bits_
+  PROTOBUF_FIELD_OFFSET(::NavParameter::SpeedLimit, _internal_metadata_),
+  ~0u,  // no _extensions_
+  ~0u,  // no _oneof_case_
+  ~0u,  // no _weak_field_map_
+  PROTOBUF_FIELD_OFFSET(::NavParameter::SpeedLimit, min_),
+  PROTOBUF_FIELD_OFFSET(::NavParameter::SpeedLimit, max_),
+  ~0u,  // no _has_bits_
+  PROTOBUF_FIELD_OFFSET(::NavParameter::Accuracy, _internal_metadata_),
+  ~0u,  // no _extensions_
+  ~0u,  // no _oneof_case_
+  ~0u,  // no _weak_field_map_
+  PROTOBUF_FIELD_OFFSET(::NavParameter::Accuracy, l_),
+  PROTOBUF_FIELD_OFFSET(::NavParameter::Accuracy, w_),
+  ~0u,  // no _has_bits_
   PROTOBUF_FIELD_OFFSET(::NavParameter::Navigation_parameter, _internal_metadata_),
   ~0u,  // no _extensions_
   ~0u,  // no _oneof_case_
@@ -170,13 +222,18 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_parameter_2eproto::offsets[] P
   PROTOBUF_FIELD_OFFSET(::NavParameter::Navigation_parameter, brother_emqx_),
   PROTOBUF_FIELD_OFFSET(::NavParameter::Navigation_parameter, x_mpc_parameter_),
   PROTOBUF_FIELD_OFFSET(::NavParameter::Navigation_parameter, y_mpc_parameter_),
+  PROTOBUF_FIELD_OFFSET(::NavParameter::Navigation_parameter, inoutvlimit_),
+  PROTOBUF_FIELD_OFFSET(::NavParameter::Navigation_parameter, nodevelocitylimit_),
+  PROTOBUF_FIELD_OFFSET(::NavParameter::Navigation_parameter, nodeangularlimit_),
 };
 static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
   { 0, -1, sizeof(::NavParameter::AgvEmqx_parameter)},
   { 11, -1, sizeof(::NavParameter::Emqx_parameter)},
   { 22, -1, sizeof(::NavParameter::BrotherEmqx)},
   { 31, -1, sizeof(::NavParameter::MPC_parameter)},
-  { 40, -1, sizeof(::NavParameter::Navigation_parameter)},
+  { 40, -1, sizeof(::NavParameter::SpeedLimit)},
+  { 47, -1, sizeof(::NavParameter::Accuracy)},
+  { 54, -1, sizeof(::NavParameter::Navigation_parameter)},
 };
 
 static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = {
@@ -184,6 +241,8 @@ static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] =
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavParameter::_Emqx_parameter_default_instance_),
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavParameter::_BrotherEmqx_default_instance_),
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavParameter::_MPC_parameter_default_instance_),
+  reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavParameter::_SpeedLimit_default_instance_),
+  reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavParameter::_Accuracy_default_instance_),
   reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::NavParameter::_Navigation_parameter_default_instance_),
 };
 
@@ -200,30 +259,38 @@ const char descriptor_table_protodef_parameter_2eproto[] PROTOBUF_SECTION_VARIAB
   "bBrotherStatuTopic\030\004 \001(\t\"_\n\rMPC_paramete"
   "r\022\027\n\017shortest_radius\030\001 \001(\002\022\n\n\002dt\030\002 \001(\002\022\024"
   "\n\014acc_velocity\030\003 \001(\002\022\023\n\013acc_angular\030\004 \001("
-  "\002\"\255\002\n\024Navigation_parameter\022\020\n\010main_agv\030\001"
-  " \001(\010\0221\n\010Agv_emqx\030\002 \001(\0132\037.NavParameter.Ag"
-  "vEmqx_parameter\0223\n\rTerminal_emqx\030\003 \001(\0132\034"
-  ".NavParameter.Emqx_parameter\022/\n\014brother_"
-  "emqx\030\004 \001(\0132\031.NavParameter.BrotherEmqx\0224\n"
-  "\017x_mpc_parameter\030\005 \001(\0132\033.NavParameter.MP"
-  "C_parameter\0224\n\017y_mpc_parameter\030\006 \001(\0132\033.N"
-  "avParameter.MPC_parameterb\006proto3"
+  "\002\"&\n\nSpeedLimit\022\013\n\003min\030\001 \001(\002\022\013\n\003max\030\002 \001("
+  "\002\" \n\010Accuracy\022\t\n\001l\030\001 \001(\002\022\t\n\001w\030\002 \001(\002\"\305\003\n\024"
+  "Navigation_parameter\022\020\n\010main_agv\030\001 \001(\010\0221"
+  "\n\010Agv_emqx\030\002 \001(\0132\037.NavParameter.AgvEmqx_"
+  "parameter\0223\n\rTerminal_emqx\030\003 \001(\0132\034.NavPa"
+  "rameter.Emqx_parameter\022/\n\014brother_emqx\030\004"
+  " \001(\0132\031.NavParameter.BrotherEmqx\0224\n\017x_mpc"
+  "_parameter\030\005 \001(\0132\033.NavParameter.MPC_para"
+  "meter\0224\n\017y_mpc_parameter\030\006 \001(\0132\033.NavPara"
+  "meter.MPC_parameter\022-\n\013InOutVLimit\030\007 \001(\013"
+  "2\030.NavParameter.SpeedLimit\0223\n\021NodeVeloci"
+  "tyLimit\030\010 \001(\0132\030.NavParameter.SpeedLimit\022"
+  "2\n\020NodeAngularLimit\030\t \001(\0132\030.NavParameter"
+  ".SpeedLimitb\006proto3"
   ;
 static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_parameter_2eproto_deps[1] = {
 };
-static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_parameter_2eproto_sccs[5] = {
+static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_parameter_2eproto_sccs[7] = {
+  &scc_info_Accuracy_parameter_2eproto.base,
   &scc_info_AgvEmqx_parameter_parameter_2eproto.base,
   &scc_info_BrotherEmqx_parameter_2eproto.base,
   &scc_info_Emqx_parameter_parameter_2eproto.base,
   &scc_info_MPC_parameter_parameter_2eproto.base,
   &scc_info_Navigation_parameter_parameter_2eproto.base,
+  &scc_info_SpeedLimit_parameter_2eproto.base,
 };
 static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_parameter_2eproto_once;
 const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_parameter_2eproto = {
-  false, false, descriptor_table_protodef_parameter_2eproto, "parameter.proto", 793,
-  &descriptor_table_parameter_2eproto_once, descriptor_table_parameter_2eproto_sccs, descriptor_table_parameter_2eproto_deps, 5, 0,
+  false, false, descriptor_table_protodef_parameter_2eproto, "parameter.proto", 1019,
+  &descriptor_table_parameter_2eproto_once, descriptor_table_parameter_2eproto_sccs, descriptor_table_parameter_2eproto_deps, 7, 0,
   schemas, file_default_instances, TableStruct_parameter_2eproto::offsets,
-  file_level_metadata_parameter_2eproto, 5, file_level_enum_descriptors_parameter_2eproto, file_level_service_descriptors_parameter_2eproto,
+  file_level_metadata_parameter_2eproto, 7, file_level_enum_descriptors_parameter_2eproto, file_level_service_descriptors_parameter_2eproto,
 };
 
 // Force running AddDescriptors() at dynamic initialization time.
@@ -1587,6 +1654,460 @@ void MPC_parameter::InternalSwap(MPC_parameter* other) {
 }
 
 
+// ===================================================================
+
+void SpeedLimit::InitAsDefaultInstance() {
+}
+class SpeedLimit::_Internal {
+ public:
+};
+
+SpeedLimit::SpeedLimit(::PROTOBUF_NAMESPACE_ID::Arena* arena)
+  : ::PROTOBUF_NAMESPACE_ID::Message(arena) {
+  SharedCtor();
+  RegisterArenaDtor(arena);
+  // @@protoc_insertion_point(arena_constructor:NavParameter.SpeedLimit)
+}
+SpeedLimit::SpeedLimit(const SpeedLimit& from)
+  : ::PROTOBUF_NAMESPACE_ID::Message() {
+  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
+  ::memcpy(&min_, &from.min_,
+    static_cast<size_t>(reinterpret_cast<char*>(&max_) -
+    reinterpret_cast<char*>(&min_)) + sizeof(max_));
+  // @@protoc_insertion_point(copy_constructor:NavParameter.SpeedLimit)
+}
+
+void SpeedLimit::SharedCtor() {
+  ::memset(&min_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&max_) -
+      reinterpret_cast<char*>(&min_)) + sizeof(max_));
+}
+
+SpeedLimit::~SpeedLimit() {
+  // @@protoc_insertion_point(destructor:NavParameter.SpeedLimit)
+  SharedDtor();
+  _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+}
+
+void SpeedLimit::SharedDtor() {
+  GOOGLE_DCHECK(GetArena() == nullptr);
+}
+
+void SpeedLimit::ArenaDtor(void* object) {
+  SpeedLimit* _this = reinterpret_cast< SpeedLimit* >(object);
+  (void)_this;
+}
+void SpeedLimit::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) {
+}
+void SpeedLimit::SetCachedSize(int size) const {
+  _cached_size_.Set(size);
+}
+const SpeedLimit& SpeedLimit::default_instance() {
+  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&::scc_info_SpeedLimit_parameter_2eproto.base);
+  return *internal_default_instance();
+}
+
+
+void SpeedLimit::Clear() {
+// @@protoc_insertion_point(message_clear_start:NavParameter.SpeedLimit)
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  // Prevent compiler warnings about cached_has_bits being unused
+  (void) cached_has_bits;
+
+  ::memset(&min_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&max_) -
+      reinterpret_cast<char*>(&min_)) + sizeof(max_));
+  _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+}
+
+const char* SpeedLimit::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) {
+#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure
+  ::PROTOBUF_NAMESPACE_ID::Arena* arena = GetArena(); (void)arena;
+  while (!ctx->Done(&ptr)) {
+    ::PROTOBUF_NAMESPACE_ID::uint32 tag;
+    ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag);
+    CHK_(ptr);
+    switch (tag >> 3) {
+      // float min = 1;
+      case 1:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 13)) {
+          min_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // float max = 2;
+      case 2:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 21)) {
+          max_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      default: {
+      handle_unusual:
+        if ((tag & 7) == 4 || tag == 0) {
+          ctx->SetLastTag(tag);
+          goto success;
+        }
+        ptr = UnknownFieldParse(tag,
+            _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(),
+            ptr, ctx);
+        CHK_(ptr != nullptr);
+        continue;
+      }
+    }  // switch
+  }  // while
+success:
+  return ptr;
+failure:
+  ptr = nullptr;
+  goto success;
+#undef CHK_
+}
+
+::PROTOBUF_NAMESPACE_ID::uint8* SpeedLimit::_InternalSerialize(
+    ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const {
+  // @@protoc_insertion_point(serialize_to_array_start:NavParameter.SpeedLimit)
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  // float min = 1;
+  if (!(this->min() <= 0 && this->min() >= 0)) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_min(), target);
+  }
+
+  // float max = 2;
+  if (!(this->max() <= 0 && this->max() >= 0)) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(2, this->_internal_max(), target);
+  }
+
+  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
+        _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
+  }
+  // @@protoc_insertion_point(serialize_to_array_end:NavParameter.SpeedLimit)
+  return target;
+}
+
+size_t SpeedLimit::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:NavParameter.SpeedLimit)
+  size_t total_size = 0;
+
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  // Prevent compiler warnings about cached_has_bits being unused
+  (void) cached_has_bits;
+
+  // float min = 1;
+  if (!(this->min() <= 0 && this->min() >= 0)) {
+    total_size += 1 + 4;
+  }
+
+  // float max = 2;
+  if (!(this->max() <= 0 && this->max() >= 0)) {
+    total_size += 1 + 4;
+  }
+
+  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
+    return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize(
+        _internal_metadata_, total_size, &_cached_size_);
+  }
+  int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size);
+  SetCachedSize(cached_size);
+  return total_size;
+}
+
+void SpeedLimit::MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
+// @@protoc_insertion_point(generalized_merge_from_start:NavParameter.SpeedLimit)
+  GOOGLE_DCHECK_NE(&from, this);
+  const SpeedLimit* source =
+      ::PROTOBUF_NAMESPACE_ID::DynamicCastToGenerated<SpeedLimit>(
+          &from);
+  if (source == nullptr) {
+  // @@protoc_insertion_point(generalized_merge_from_cast_fail:NavParameter.SpeedLimit)
+    ::PROTOBUF_NAMESPACE_ID::internal::ReflectionOps::Merge(from, this);
+  } else {
+  // @@protoc_insertion_point(generalized_merge_from_cast_success:NavParameter.SpeedLimit)
+    MergeFrom(*source);
+  }
+}
+
+void SpeedLimit::MergeFrom(const SpeedLimit& from) {
+// @@protoc_insertion_point(class_specific_merge_from_start:NavParameter.SpeedLimit)
+  GOOGLE_DCHECK_NE(&from, this);
+  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  if (!(from.min() <= 0 && from.min() >= 0)) {
+    _internal_set_min(from._internal_min());
+  }
+  if (!(from.max() <= 0 && from.max() >= 0)) {
+    _internal_set_max(from._internal_max());
+  }
+}
+
+void SpeedLimit::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:NavParameter.SpeedLimit)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+void SpeedLimit::CopyFrom(const SpeedLimit& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:NavParameter.SpeedLimit)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+bool SpeedLimit::IsInitialized() const {
+  return true;
+}
+
+void SpeedLimit::InternalSwap(SpeedLimit* other) {
+  using std::swap;
+  _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
+  ::PROTOBUF_NAMESPACE_ID::internal::memswap<
+      PROTOBUF_FIELD_OFFSET(SpeedLimit, max_)
+      + sizeof(SpeedLimit::max_)
+      - PROTOBUF_FIELD_OFFSET(SpeedLimit, min_)>(
+          reinterpret_cast<char*>(&min_),
+          reinterpret_cast<char*>(&other->min_));
+}
+
+::PROTOBUF_NAMESPACE_ID::Metadata SpeedLimit::GetMetadata() const {
+  return GetMetadataStatic();
+}
+
+
+// ===================================================================
+
+void Accuracy::InitAsDefaultInstance() {
+}
+class Accuracy::_Internal {
+ public:
+};
+
+Accuracy::Accuracy(::PROTOBUF_NAMESPACE_ID::Arena* arena)
+  : ::PROTOBUF_NAMESPACE_ID::Message(arena) {
+  SharedCtor();
+  RegisterArenaDtor(arena);
+  // @@protoc_insertion_point(arena_constructor:NavParameter.Accuracy)
+}
+Accuracy::Accuracy(const Accuracy& from)
+  : ::PROTOBUF_NAMESPACE_ID::Message() {
+  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
+  ::memcpy(&l_, &from.l_,
+    static_cast<size_t>(reinterpret_cast<char*>(&w_) -
+    reinterpret_cast<char*>(&l_)) + sizeof(w_));
+  // @@protoc_insertion_point(copy_constructor:NavParameter.Accuracy)
+}
+
+void Accuracy::SharedCtor() {
+  ::memset(&l_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&w_) -
+      reinterpret_cast<char*>(&l_)) + sizeof(w_));
+}
+
+Accuracy::~Accuracy() {
+  // @@protoc_insertion_point(destructor:NavParameter.Accuracy)
+  SharedDtor();
+  _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+}
+
+void Accuracy::SharedDtor() {
+  GOOGLE_DCHECK(GetArena() == nullptr);
+}
+
+void Accuracy::ArenaDtor(void* object) {
+  Accuracy* _this = reinterpret_cast< Accuracy* >(object);
+  (void)_this;
+}
+void Accuracy::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) {
+}
+void Accuracy::SetCachedSize(int size) const {
+  _cached_size_.Set(size);
+}
+const Accuracy& Accuracy::default_instance() {
+  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&::scc_info_Accuracy_parameter_2eproto.base);
+  return *internal_default_instance();
+}
+
+
+void Accuracy::Clear() {
+// @@protoc_insertion_point(message_clear_start:NavParameter.Accuracy)
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  // Prevent compiler warnings about cached_has_bits being unused
+  (void) cached_has_bits;
+
+  ::memset(&l_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&w_) -
+      reinterpret_cast<char*>(&l_)) + sizeof(w_));
+  _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+}
+
+const char* Accuracy::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) {
+#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure
+  ::PROTOBUF_NAMESPACE_ID::Arena* arena = GetArena(); (void)arena;
+  while (!ctx->Done(&ptr)) {
+    ::PROTOBUF_NAMESPACE_ID::uint32 tag;
+    ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag);
+    CHK_(ptr);
+    switch (tag >> 3) {
+      // float l = 1;
+      case 1:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 13)) {
+          l_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // float w = 2;
+      case 2:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 21)) {
+          w_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      default: {
+      handle_unusual:
+        if ((tag & 7) == 4 || tag == 0) {
+          ctx->SetLastTag(tag);
+          goto success;
+        }
+        ptr = UnknownFieldParse(tag,
+            _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(),
+            ptr, ctx);
+        CHK_(ptr != nullptr);
+        continue;
+      }
+    }  // switch
+  }  // while
+success:
+  return ptr;
+failure:
+  ptr = nullptr;
+  goto success;
+#undef CHK_
+}
+
+::PROTOBUF_NAMESPACE_ID::uint8* Accuracy::_InternalSerialize(
+    ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const {
+  // @@protoc_insertion_point(serialize_to_array_start:NavParameter.Accuracy)
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  // float l = 1;
+  if (!(this->l() <= 0 && this->l() >= 0)) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_l(), target);
+  }
+
+  // float w = 2;
+  if (!(this->w() <= 0 && this->w() >= 0)) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(2, this->_internal_w(), target);
+  }
+
+  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
+        _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
+  }
+  // @@protoc_insertion_point(serialize_to_array_end:NavParameter.Accuracy)
+  return target;
+}
+
+size_t Accuracy::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:NavParameter.Accuracy)
+  size_t total_size = 0;
+
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  // Prevent compiler warnings about cached_has_bits being unused
+  (void) cached_has_bits;
+
+  // float l = 1;
+  if (!(this->l() <= 0 && this->l() >= 0)) {
+    total_size += 1 + 4;
+  }
+
+  // float w = 2;
+  if (!(this->w() <= 0 && this->w() >= 0)) {
+    total_size += 1 + 4;
+  }
+
+  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
+    return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize(
+        _internal_metadata_, total_size, &_cached_size_);
+  }
+  int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size);
+  SetCachedSize(cached_size);
+  return total_size;
+}
+
+void Accuracy::MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
+// @@protoc_insertion_point(generalized_merge_from_start:NavParameter.Accuracy)
+  GOOGLE_DCHECK_NE(&from, this);
+  const Accuracy* source =
+      ::PROTOBUF_NAMESPACE_ID::DynamicCastToGenerated<Accuracy>(
+          &from);
+  if (source == nullptr) {
+  // @@protoc_insertion_point(generalized_merge_from_cast_fail:NavParameter.Accuracy)
+    ::PROTOBUF_NAMESPACE_ID::internal::ReflectionOps::Merge(from, this);
+  } else {
+  // @@protoc_insertion_point(generalized_merge_from_cast_success:NavParameter.Accuracy)
+    MergeFrom(*source);
+  }
+}
+
+void Accuracy::MergeFrom(const Accuracy& from) {
+// @@protoc_insertion_point(class_specific_merge_from_start:NavParameter.Accuracy)
+  GOOGLE_DCHECK_NE(&from, this);
+  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  if (!(from.l() <= 0 && from.l() >= 0)) {
+    _internal_set_l(from._internal_l());
+  }
+  if (!(from.w() <= 0 && from.w() >= 0)) {
+    _internal_set_w(from._internal_w());
+  }
+}
+
+void Accuracy::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:NavParameter.Accuracy)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+void Accuracy::CopyFrom(const Accuracy& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:NavParameter.Accuracy)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+bool Accuracy::IsInitialized() const {
+  return true;
+}
+
+void Accuracy::InternalSwap(Accuracy* other) {
+  using std::swap;
+  _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
+  ::PROTOBUF_NAMESPACE_ID::internal::memswap<
+      PROTOBUF_FIELD_OFFSET(Accuracy, w_)
+      + sizeof(Accuracy::w_)
+      - PROTOBUF_FIELD_OFFSET(Accuracy, l_)>(
+          reinterpret_cast<char*>(&l_),
+          reinterpret_cast<char*>(&other->l_));
+}
+
+::PROTOBUF_NAMESPACE_ID::Metadata Accuracy::GetMetadata() const {
+  return GetMetadataStatic();
+}
+
+
 // ===================================================================
 
 void Navigation_parameter::InitAsDefaultInstance() {
@@ -1600,6 +2121,12 @@ void Navigation_parameter::InitAsDefaultInstance() {
       ::NavParameter::MPC_parameter::internal_default_instance());
   ::NavParameter::_Navigation_parameter_default_instance_._instance.get_mutable()->y_mpc_parameter_ = const_cast< ::NavParameter::MPC_parameter*>(
       ::NavParameter::MPC_parameter::internal_default_instance());
+  ::NavParameter::_Navigation_parameter_default_instance_._instance.get_mutable()->inoutvlimit_ = const_cast< ::NavParameter::SpeedLimit*>(
+      ::NavParameter::SpeedLimit::internal_default_instance());
+  ::NavParameter::_Navigation_parameter_default_instance_._instance.get_mutable()->nodevelocitylimit_ = const_cast< ::NavParameter::SpeedLimit*>(
+      ::NavParameter::SpeedLimit::internal_default_instance());
+  ::NavParameter::_Navigation_parameter_default_instance_._instance.get_mutable()->nodeangularlimit_ = const_cast< ::NavParameter::SpeedLimit*>(
+      ::NavParameter::SpeedLimit::internal_default_instance());
 }
 class Navigation_parameter::_Internal {
  public:
@@ -1608,6 +2135,9 @@ class Navigation_parameter::_Internal {
   static const ::NavParameter::BrotherEmqx& brother_emqx(const Navigation_parameter* msg);
   static const ::NavParameter::MPC_parameter& x_mpc_parameter(const Navigation_parameter* msg);
   static const ::NavParameter::MPC_parameter& y_mpc_parameter(const Navigation_parameter* msg);
+  static const ::NavParameter::SpeedLimit& inoutvlimit(const Navigation_parameter* msg);
+  static const ::NavParameter::SpeedLimit& nodevelocitylimit(const Navigation_parameter* msg);
+  static const ::NavParameter::SpeedLimit& nodeangularlimit(const Navigation_parameter* msg);
 };
 
 const ::NavParameter::AgvEmqx_parameter&
@@ -1630,6 +2160,18 @@ const ::NavParameter::MPC_parameter&
 Navigation_parameter::_Internal::y_mpc_parameter(const Navigation_parameter* msg) {
   return *msg->y_mpc_parameter_;
 }
+const ::NavParameter::SpeedLimit&
+Navigation_parameter::_Internal::inoutvlimit(const Navigation_parameter* msg) {
+  return *msg->inoutvlimit_;
+}
+const ::NavParameter::SpeedLimit&
+Navigation_parameter::_Internal::nodevelocitylimit(const Navigation_parameter* msg) {
+  return *msg->nodevelocitylimit_;
+}
+const ::NavParameter::SpeedLimit&
+Navigation_parameter::_Internal::nodeangularlimit(const Navigation_parameter* msg) {
+  return *msg->nodeangularlimit_;
+}
 Navigation_parameter::Navigation_parameter(::PROTOBUF_NAMESPACE_ID::Arena* arena)
   : ::PROTOBUF_NAMESPACE_ID::Message(arena) {
   SharedCtor();
@@ -1664,6 +2206,21 @@ Navigation_parameter::Navigation_parameter(const Navigation_parameter& from)
   } else {
     y_mpc_parameter_ = nullptr;
   }
+  if (from._internal_has_inoutvlimit()) {
+    inoutvlimit_ = new ::NavParameter::SpeedLimit(*from.inoutvlimit_);
+  } else {
+    inoutvlimit_ = nullptr;
+  }
+  if (from._internal_has_nodevelocitylimit()) {
+    nodevelocitylimit_ = new ::NavParameter::SpeedLimit(*from.nodevelocitylimit_);
+  } else {
+    nodevelocitylimit_ = nullptr;
+  }
+  if (from._internal_has_nodeangularlimit()) {
+    nodeangularlimit_ = new ::NavParameter::SpeedLimit(*from.nodeangularlimit_);
+  } else {
+    nodeangularlimit_ = nullptr;
+  }
   main_agv_ = from.main_agv_;
   // @@protoc_insertion_point(copy_constructor:NavParameter.Navigation_parameter)
 }
@@ -1688,6 +2245,9 @@ void Navigation_parameter::SharedDtor() {
   if (this != internal_default_instance()) delete brother_emqx_;
   if (this != internal_default_instance()) delete x_mpc_parameter_;
   if (this != internal_default_instance()) delete y_mpc_parameter_;
+  if (this != internal_default_instance()) delete inoutvlimit_;
+  if (this != internal_default_instance()) delete nodevelocitylimit_;
+  if (this != internal_default_instance()) delete nodeangularlimit_;
 }
 
 void Navigation_parameter::ArenaDtor(void* object) {
@@ -1731,6 +2291,18 @@ void Navigation_parameter::Clear() {
     delete y_mpc_parameter_;
   }
   y_mpc_parameter_ = nullptr;
+  if (GetArena() == nullptr && inoutvlimit_ != nullptr) {
+    delete inoutvlimit_;
+  }
+  inoutvlimit_ = nullptr;
+  if (GetArena() == nullptr && nodevelocitylimit_ != nullptr) {
+    delete nodevelocitylimit_;
+  }
+  nodevelocitylimit_ = nullptr;
+  if (GetArena() == nullptr && nodeangularlimit_ != nullptr) {
+    delete nodeangularlimit_;
+  }
+  nodeangularlimit_ = nullptr;
   main_agv_ = false;
   _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
 }
@@ -1785,6 +2357,27 @@ const char* Navigation_parameter::_InternalParse(const char* ptr, ::PROTOBUF_NAM
           CHK_(ptr);
         } else goto handle_unusual;
         continue;
+      // .NavParameter.SpeedLimit InOutVLimit = 7;
+      case 7:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 58)) {
+          ptr = ctx->ParseMessage(_internal_mutable_inoutvlimit(), ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // .NavParameter.SpeedLimit NodeVelocityLimit = 8;
+      case 8:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 66)) {
+          ptr = ctx->ParseMessage(_internal_mutable_nodevelocitylimit(), ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // .NavParameter.SpeedLimit NodeAngularLimit = 9;
+      case 9:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 74)) {
+          ptr = ctx->ParseMessage(_internal_mutable_nodeangularlimit(), ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
       default: {
       handle_unusual:
         if ((tag & 7) == 4 || tag == 0) {
@@ -1859,6 +2452,30 @@ failure:
         6, _Internal::y_mpc_parameter(this), target, stream);
   }
 
+  // .NavParameter.SpeedLimit InOutVLimit = 7;
+  if (this->has_inoutvlimit()) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
+      InternalWriteMessage(
+        7, _Internal::inoutvlimit(this), target, stream);
+  }
+
+  // .NavParameter.SpeedLimit NodeVelocityLimit = 8;
+  if (this->has_nodevelocitylimit()) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
+      InternalWriteMessage(
+        8, _Internal::nodevelocitylimit(this), target, stream);
+  }
+
+  // .NavParameter.SpeedLimit NodeAngularLimit = 9;
+  if (this->has_nodeangularlimit()) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
+      InternalWriteMessage(
+        9, _Internal::nodeangularlimit(this), target, stream);
+  }
+
   if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
     target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
         _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
@@ -1910,6 +2527,27 @@ size_t Navigation_parameter::ByteSizeLong() const {
         *y_mpc_parameter_);
   }
 
+  // .NavParameter.SpeedLimit InOutVLimit = 7;
+  if (this->has_inoutvlimit()) {
+    total_size += 1 +
+      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
+        *inoutvlimit_);
+  }
+
+  // .NavParameter.SpeedLimit NodeVelocityLimit = 8;
+  if (this->has_nodevelocitylimit()) {
+    total_size += 1 +
+      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
+        *nodevelocitylimit_);
+  }
+
+  // .NavParameter.SpeedLimit NodeAngularLimit = 9;
+  if (this->has_nodeangularlimit()) {
+    total_size += 1 +
+      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
+        *nodeangularlimit_);
+  }
+
   // bool main_agv = 1;
   if (this->main_agv() != 0) {
     total_size += 1 + 1;
@@ -1961,6 +2599,15 @@ void Navigation_parameter::MergeFrom(const Navigation_parameter& from) {
   if (from.has_y_mpc_parameter()) {
     _internal_mutable_y_mpc_parameter()->::NavParameter::MPC_parameter::MergeFrom(from._internal_y_mpc_parameter());
   }
+  if (from.has_inoutvlimit()) {
+    _internal_mutable_inoutvlimit()->::NavParameter::SpeedLimit::MergeFrom(from._internal_inoutvlimit());
+  }
+  if (from.has_nodevelocitylimit()) {
+    _internal_mutable_nodevelocitylimit()->::NavParameter::SpeedLimit::MergeFrom(from._internal_nodevelocitylimit());
+  }
+  if (from.has_nodeangularlimit()) {
+    _internal_mutable_nodeangularlimit()->::NavParameter::SpeedLimit::MergeFrom(from._internal_nodeangularlimit());
+  }
   if (from.main_agv() != 0) {
     _internal_set_main_agv(from._internal_main_agv());
   }
@@ -2015,6 +2662,12 @@ template<> PROTOBUF_NOINLINE ::NavParameter::BrotherEmqx* Arena::CreateMaybeMess
 template<> PROTOBUF_NOINLINE ::NavParameter::MPC_parameter* Arena::CreateMaybeMessage< ::NavParameter::MPC_parameter >(Arena* arena) {
   return Arena::CreateMessageInternal< ::NavParameter::MPC_parameter >(arena);
 }
+template<> PROTOBUF_NOINLINE ::NavParameter::SpeedLimit* Arena::CreateMaybeMessage< ::NavParameter::SpeedLimit >(Arena* arena) {
+  return Arena::CreateMessageInternal< ::NavParameter::SpeedLimit >(arena);
+}
+template<> PROTOBUF_NOINLINE ::NavParameter::Accuracy* Arena::CreateMaybeMessage< ::NavParameter::Accuracy >(Arena* arena) {
+  return Arena::CreateMessageInternal< ::NavParameter::Accuracy >(arena);
+}
 template<> PROTOBUF_NOINLINE ::NavParameter::Navigation_parameter* Arena::CreateMaybeMessage< ::NavParameter::Navigation_parameter >(Arena* arena) {
   return Arena::CreateMessageInternal< ::NavParameter::Navigation_parameter >(arena);
 }

+ 707 - 2
MPC/parameter.pb.h

@@ -47,7 +47,7 @@ struct TableStruct_parameter_2eproto {
     PROTOBUF_SECTION_VARIABLE(protodesc_cold);
   static const ::PROTOBUF_NAMESPACE_ID::internal::AuxiliaryParseTableField aux[]
     PROTOBUF_SECTION_VARIABLE(protodesc_cold);
-  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[5]
+  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[7]
     PROTOBUF_SECTION_VARIABLE(protodesc_cold);
   static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[];
   static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[];
@@ -55,6 +55,9 @@ struct TableStruct_parameter_2eproto {
 };
 extern const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_parameter_2eproto;
 namespace NavParameter {
+class Accuracy;
+class AccuracyDefaultTypeInternal;
+extern AccuracyDefaultTypeInternal _Accuracy_default_instance_;
 class AgvEmqx_parameter;
 class AgvEmqx_parameterDefaultTypeInternal;
 extern AgvEmqx_parameterDefaultTypeInternal _AgvEmqx_parameter_default_instance_;
@@ -70,13 +73,18 @@ extern MPC_parameterDefaultTypeInternal _MPC_parameter_default_instance_;
 class Navigation_parameter;
 class Navigation_parameterDefaultTypeInternal;
 extern Navigation_parameterDefaultTypeInternal _Navigation_parameter_default_instance_;
+class SpeedLimit;
+class SpeedLimitDefaultTypeInternal;
+extern SpeedLimitDefaultTypeInternal _SpeedLimit_default_instance_;
 }  // namespace NavParameter
 PROTOBUF_NAMESPACE_OPEN
+template<> ::NavParameter::Accuracy* Arena::CreateMaybeMessage<::NavParameter::Accuracy>(Arena*);
 template<> ::NavParameter::AgvEmqx_parameter* Arena::CreateMaybeMessage<::NavParameter::AgvEmqx_parameter>(Arena*);
 template<> ::NavParameter::BrotherEmqx* Arena::CreateMaybeMessage<::NavParameter::BrotherEmqx>(Arena*);
 template<> ::NavParameter::Emqx_parameter* Arena::CreateMaybeMessage<::NavParameter::Emqx_parameter>(Arena*);
 template<> ::NavParameter::MPC_parameter* Arena::CreateMaybeMessage<::NavParameter::MPC_parameter>(Arena*);
 template<> ::NavParameter::Navigation_parameter* Arena::CreateMaybeMessage<::NavParameter::Navigation_parameter>(Arena*);
+template<> ::NavParameter::SpeedLimit* Arena::CreateMaybeMessage<::NavParameter::SpeedLimit>(Arena*);
 PROTOBUF_NAMESPACE_CLOSE
 namespace NavParameter {
 
@@ -897,6 +905,302 @@ class MPC_parameter PROTOBUF_FINAL :
 };
 // -------------------------------------------------------------------
 
+class SpeedLimit PROTOBUF_FINAL :
+    public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:NavParameter.SpeedLimit) */ {
+ public:
+  inline SpeedLimit() : SpeedLimit(nullptr) {}
+  virtual ~SpeedLimit();
+
+  SpeedLimit(const SpeedLimit& from);
+  SpeedLimit(SpeedLimit&& from) noexcept
+    : SpeedLimit() {
+    *this = ::std::move(from);
+  }
+
+  inline SpeedLimit& operator=(const SpeedLimit& from) {
+    CopyFrom(from);
+    return *this;
+  }
+  inline SpeedLimit& operator=(SpeedLimit&& from) noexcept {
+    if (GetArena() == from.GetArena()) {
+      if (this != &from) InternalSwap(&from);
+    } else {
+      CopyFrom(from);
+    }
+    return *this;
+  }
+
+  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() {
+    return GetDescriptor();
+  }
+  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() {
+    return GetMetadataStatic().descriptor;
+  }
+  static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() {
+    return GetMetadataStatic().reflection;
+  }
+  static const SpeedLimit& default_instance();
+
+  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
+  static inline const SpeedLimit* internal_default_instance() {
+    return reinterpret_cast<const SpeedLimit*>(
+               &_SpeedLimit_default_instance_);
+  }
+  static constexpr int kIndexInFileMessages =
+    4;
+
+  friend void swap(SpeedLimit& a, SpeedLimit& b) {
+    a.Swap(&b);
+  }
+  inline void Swap(SpeedLimit* other) {
+    if (other == this) return;
+    if (GetArena() == other->GetArena()) {
+      InternalSwap(other);
+    } else {
+      ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other);
+    }
+  }
+  void UnsafeArenaSwap(SpeedLimit* other) {
+    if (other == this) return;
+    GOOGLE_DCHECK(GetArena() == other->GetArena());
+    InternalSwap(other);
+  }
+
+  // implements Message ----------------------------------------------
+
+  inline SpeedLimit* New() const final {
+    return CreateMaybeMessage<SpeedLimit>(nullptr);
+  }
+
+  SpeedLimit* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final {
+    return CreateMaybeMessage<SpeedLimit>(arena);
+  }
+  void CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
+  void MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
+  void CopyFrom(const SpeedLimit& from);
+  void MergeFrom(const SpeedLimit& from);
+  PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final;
+  bool IsInitialized() const final;
+
+  size_t ByteSizeLong() const final;
+  const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final;
+  ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize(
+      ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final;
+  int GetCachedSize() const final { return _cached_size_.Get(); }
+
+  private:
+  inline void SharedCtor();
+  inline void SharedDtor();
+  void SetCachedSize(int size) const final;
+  void InternalSwap(SpeedLimit* other);
+  friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata;
+  static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() {
+    return "NavParameter.SpeedLimit";
+  }
+  protected:
+  explicit SpeedLimit(::PROTOBUF_NAMESPACE_ID::Arena* arena);
+  private:
+  static void ArenaDtor(void* object);
+  inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena);
+  public:
+
+  ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final;
+  private:
+  static ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadataStatic() {
+    ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&::descriptor_table_parameter_2eproto);
+    return ::descriptor_table_parameter_2eproto.file_level_metadata[kIndexInFileMessages];
+  }
+
+  public:
+
+  // nested types ----------------------------------------------------
+
+  // accessors -------------------------------------------------------
+
+  enum : int {
+    kMinFieldNumber = 1,
+    kMaxFieldNumber = 2,
+  };
+  // float min = 1;
+  void clear_min();
+  float min() const;
+  void set_min(float value);
+  private:
+  float _internal_min() const;
+  void _internal_set_min(float value);
+  public:
+
+  // float max = 2;
+  void clear_max();
+  float max() const;
+  void set_max(float value);
+  private:
+  float _internal_max() const;
+  void _internal_set_max(float value);
+  public:
+
+  // @@protoc_insertion_point(class_scope:NavParameter.SpeedLimit)
+ private:
+  class _Internal;
+
+  template <typename T> friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper;
+  typedef void InternalArenaConstructable_;
+  typedef void DestructorSkippable_;
+  float min_;
+  float max_;
+  mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
+  friend struct ::TableStruct_parameter_2eproto;
+};
+// -------------------------------------------------------------------
+
+class Accuracy PROTOBUF_FINAL :
+    public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:NavParameter.Accuracy) */ {
+ public:
+  inline Accuracy() : Accuracy(nullptr) {}
+  virtual ~Accuracy();
+
+  Accuracy(const Accuracy& from);
+  Accuracy(Accuracy&& from) noexcept
+    : Accuracy() {
+    *this = ::std::move(from);
+  }
+
+  inline Accuracy& operator=(const Accuracy& from) {
+    CopyFrom(from);
+    return *this;
+  }
+  inline Accuracy& operator=(Accuracy&& from) noexcept {
+    if (GetArena() == from.GetArena()) {
+      if (this != &from) InternalSwap(&from);
+    } else {
+      CopyFrom(from);
+    }
+    return *this;
+  }
+
+  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() {
+    return GetDescriptor();
+  }
+  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() {
+    return GetMetadataStatic().descriptor;
+  }
+  static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() {
+    return GetMetadataStatic().reflection;
+  }
+  static const Accuracy& default_instance();
+
+  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
+  static inline const Accuracy* internal_default_instance() {
+    return reinterpret_cast<const Accuracy*>(
+               &_Accuracy_default_instance_);
+  }
+  static constexpr int kIndexInFileMessages =
+    5;
+
+  friend void swap(Accuracy& a, Accuracy& b) {
+    a.Swap(&b);
+  }
+  inline void Swap(Accuracy* other) {
+    if (other == this) return;
+    if (GetArena() == other->GetArena()) {
+      InternalSwap(other);
+    } else {
+      ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other);
+    }
+  }
+  void UnsafeArenaSwap(Accuracy* other) {
+    if (other == this) return;
+    GOOGLE_DCHECK(GetArena() == other->GetArena());
+    InternalSwap(other);
+  }
+
+  // implements Message ----------------------------------------------
+
+  inline Accuracy* New() const final {
+    return CreateMaybeMessage<Accuracy>(nullptr);
+  }
+
+  Accuracy* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final {
+    return CreateMaybeMessage<Accuracy>(arena);
+  }
+  void CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
+  void MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
+  void CopyFrom(const Accuracy& from);
+  void MergeFrom(const Accuracy& from);
+  PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final;
+  bool IsInitialized() const final;
+
+  size_t ByteSizeLong() const final;
+  const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final;
+  ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize(
+      ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final;
+  int GetCachedSize() const final { return _cached_size_.Get(); }
+
+  private:
+  inline void SharedCtor();
+  inline void SharedDtor();
+  void SetCachedSize(int size) const final;
+  void InternalSwap(Accuracy* other);
+  friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata;
+  static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() {
+    return "NavParameter.Accuracy";
+  }
+  protected:
+  explicit Accuracy(::PROTOBUF_NAMESPACE_ID::Arena* arena);
+  private:
+  static void ArenaDtor(void* object);
+  inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena);
+  public:
+
+  ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final;
+  private:
+  static ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadataStatic() {
+    ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&::descriptor_table_parameter_2eproto);
+    return ::descriptor_table_parameter_2eproto.file_level_metadata[kIndexInFileMessages];
+  }
+
+  public:
+
+  // nested types ----------------------------------------------------
+
+  // accessors -------------------------------------------------------
+
+  enum : int {
+    kLFieldNumber = 1,
+    kWFieldNumber = 2,
+  };
+  // float l = 1;
+  void clear_l();
+  float l() const;
+  void set_l(float value);
+  private:
+  float _internal_l() const;
+  void _internal_set_l(float value);
+  public:
+
+  // float w = 2;
+  void clear_w();
+  float w() const;
+  void set_w(float value);
+  private:
+  float _internal_w() const;
+  void _internal_set_w(float value);
+  public:
+
+  // @@protoc_insertion_point(class_scope:NavParameter.Accuracy)
+ private:
+  class _Internal;
+
+  template <typename T> friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper;
+  typedef void InternalArenaConstructable_;
+  typedef void DestructorSkippable_;
+  float l_;
+  float w_;
+  mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
+  friend struct ::TableStruct_parameter_2eproto;
+};
+// -------------------------------------------------------------------
+
 class Navigation_parameter PROTOBUF_FINAL :
     public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:NavParameter.Navigation_parameter) */ {
  public:
@@ -939,7 +1243,7 @@ class Navigation_parameter PROTOBUF_FINAL :
                &_Navigation_parameter_default_instance_);
   }
   static constexpr int kIndexInFileMessages =
-    4;
+    6;
 
   friend void swap(Navigation_parameter& a, Navigation_parameter& b) {
     a.Swap(&b);
@@ -1015,6 +1319,9 @@ class Navigation_parameter PROTOBUF_FINAL :
     kBrotherEmqxFieldNumber = 4,
     kXMpcParameterFieldNumber = 5,
     kYMpcParameterFieldNumber = 6,
+    kInOutVLimitFieldNumber = 7,
+    kNodeVelocityLimitFieldNumber = 8,
+    kNodeAngularLimitFieldNumber = 9,
     kMainAgvFieldNumber = 1,
   };
   // .NavParameter.AgvEmqx_parameter Agv_emqx = 2;
@@ -1107,6 +1414,60 @@ class Navigation_parameter PROTOBUF_FINAL :
       ::NavParameter::MPC_parameter* y_mpc_parameter);
   ::NavParameter::MPC_parameter* unsafe_arena_release_y_mpc_parameter();
 
+  // .NavParameter.SpeedLimit InOutVLimit = 7;
+  bool has_inoutvlimit() const;
+  private:
+  bool _internal_has_inoutvlimit() const;
+  public:
+  void clear_inoutvlimit();
+  const ::NavParameter::SpeedLimit& inoutvlimit() const;
+  ::NavParameter::SpeedLimit* release_inoutvlimit();
+  ::NavParameter::SpeedLimit* mutable_inoutvlimit();
+  void set_allocated_inoutvlimit(::NavParameter::SpeedLimit* inoutvlimit);
+  private:
+  const ::NavParameter::SpeedLimit& _internal_inoutvlimit() const;
+  ::NavParameter::SpeedLimit* _internal_mutable_inoutvlimit();
+  public:
+  void unsafe_arena_set_allocated_inoutvlimit(
+      ::NavParameter::SpeedLimit* inoutvlimit);
+  ::NavParameter::SpeedLimit* unsafe_arena_release_inoutvlimit();
+
+  // .NavParameter.SpeedLimit NodeVelocityLimit = 8;
+  bool has_nodevelocitylimit() const;
+  private:
+  bool _internal_has_nodevelocitylimit() const;
+  public:
+  void clear_nodevelocitylimit();
+  const ::NavParameter::SpeedLimit& nodevelocitylimit() const;
+  ::NavParameter::SpeedLimit* release_nodevelocitylimit();
+  ::NavParameter::SpeedLimit* mutable_nodevelocitylimit();
+  void set_allocated_nodevelocitylimit(::NavParameter::SpeedLimit* nodevelocitylimit);
+  private:
+  const ::NavParameter::SpeedLimit& _internal_nodevelocitylimit() const;
+  ::NavParameter::SpeedLimit* _internal_mutable_nodevelocitylimit();
+  public:
+  void unsafe_arena_set_allocated_nodevelocitylimit(
+      ::NavParameter::SpeedLimit* nodevelocitylimit);
+  ::NavParameter::SpeedLimit* unsafe_arena_release_nodevelocitylimit();
+
+  // .NavParameter.SpeedLimit NodeAngularLimit = 9;
+  bool has_nodeangularlimit() const;
+  private:
+  bool _internal_has_nodeangularlimit() const;
+  public:
+  void clear_nodeangularlimit();
+  const ::NavParameter::SpeedLimit& nodeangularlimit() const;
+  ::NavParameter::SpeedLimit* release_nodeangularlimit();
+  ::NavParameter::SpeedLimit* mutable_nodeangularlimit();
+  void set_allocated_nodeangularlimit(::NavParameter::SpeedLimit* nodeangularlimit);
+  private:
+  const ::NavParameter::SpeedLimit& _internal_nodeangularlimit() const;
+  ::NavParameter::SpeedLimit* _internal_mutable_nodeangularlimit();
+  public:
+  void unsafe_arena_set_allocated_nodeangularlimit(
+      ::NavParameter::SpeedLimit* nodeangularlimit);
+  ::NavParameter::SpeedLimit* unsafe_arena_release_nodeangularlimit();
+
   // bool main_agv = 1;
   void clear_main_agv();
   bool main_agv() const;
@@ -1128,6 +1489,9 @@ class Navigation_parameter PROTOBUF_FINAL :
   ::NavParameter::BrotherEmqx* brother_emqx_;
   ::NavParameter::MPC_parameter* x_mpc_parameter_;
   ::NavParameter::MPC_parameter* y_mpc_parameter_;
+  ::NavParameter::SpeedLimit* inoutvlimit_;
+  ::NavParameter::SpeedLimit* nodevelocitylimit_;
+  ::NavParameter::SpeedLimit* nodeangularlimit_;
   bool main_agv_;
   mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
   friend struct ::TableStruct_parameter_2eproto;
@@ -2103,6 +2467,94 @@ inline void MPC_parameter::set_acc_angular(float value) {
 
 // -------------------------------------------------------------------
 
+// SpeedLimit
+
+// float min = 1;
+inline void SpeedLimit::clear_min() {
+  min_ = 0;
+}
+inline float SpeedLimit::_internal_min() const {
+  return min_;
+}
+inline float SpeedLimit::min() const {
+  // @@protoc_insertion_point(field_get:NavParameter.SpeedLimit.min)
+  return _internal_min();
+}
+inline void SpeedLimit::_internal_set_min(float value) {
+  
+  min_ = value;
+}
+inline void SpeedLimit::set_min(float value) {
+  _internal_set_min(value);
+  // @@protoc_insertion_point(field_set:NavParameter.SpeedLimit.min)
+}
+
+// float max = 2;
+inline void SpeedLimit::clear_max() {
+  max_ = 0;
+}
+inline float SpeedLimit::_internal_max() const {
+  return max_;
+}
+inline float SpeedLimit::max() const {
+  // @@protoc_insertion_point(field_get:NavParameter.SpeedLimit.max)
+  return _internal_max();
+}
+inline void SpeedLimit::_internal_set_max(float value) {
+  
+  max_ = value;
+}
+inline void SpeedLimit::set_max(float value) {
+  _internal_set_max(value);
+  // @@protoc_insertion_point(field_set:NavParameter.SpeedLimit.max)
+}
+
+// -------------------------------------------------------------------
+
+// Accuracy
+
+// float l = 1;
+inline void Accuracy::clear_l() {
+  l_ = 0;
+}
+inline float Accuracy::_internal_l() const {
+  return l_;
+}
+inline float Accuracy::l() const {
+  // @@protoc_insertion_point(field_get:NavParameter.Accuracy.l)
+  return _internal_l();
+}
+inline void Accuracy::_internal_set_l(float value) {
+  
+  l_ = value;
+}
+inline void Accuracy::set_l(float value) {
+  _internal_set_l(value);
+  // @@protoc_insertion_point(field_set:NavParameter.Accuracy.l)
+}
+
+// float w = 2;
+inline void Accuracy::clear_w() {
+  w_ = 0;
+}
+inline float Accuracy::_internal_w() const {
+  return w_;
+}
+inline float Accuracy::w() const {
+  // @@protoc_insertion_point(field_get:NavParameter.Accuracy.w)
+  return _internal_w();
+}
+inline void Accuracy::_internal_set_w(float value) {
+  
+  w_ = value;
+}
+inline void Accuracy::set_w(float value) {
+  _internal_set_w(value);
+  // @@protoc_insertion_point(field_set:NavParameter.Accuracy.w)
+}
+
+// -------------------------------------------------------------------
+
 // Navigation_parameter
 
 // bool main_agv = 1;
@@ -2540,6 +2992,255 @@ inline void Navigation_parameter::set_allocated_y_mpc_parameter(::NavParameter::
   // @@protoc_insertion_point(field_set_allocated:NavParameter.Navigation_parameter.y_mpc_parameter)
 }
 
+// .NavParameter.SpeedLimit InOutVLimit = 7;
+inline bool Navigation_parameter::_internal_has_inoutvlimit() const {
+  return this != internal_default_instance() && inoutvlimit_ != nullptr;
+}
+inline bool Navigation_parameter::has_inoutvlimit() const {
+  return _internal_has_inoutvlimit();
+}
+inline void Navigation_parameter::clear_inoutvlimit() {
+  if (GetArena() == nullptr && inoutvlimit_ != nullptr) {
+    delete inoutvlimit_;
+  }
+  inoutvlimit_ = nullptr;
+}
+inline const ::NavParameter::SpeedLimit& Navigation_parameter::_internal_inoutvlimit() const {
+  const ::NavParameter::SpeedLimit* p = inoutvlimit_;
+  return p != nullptr ? *p : *reinterpret_cast<const ::NavParameter::SpeedLimit*>(
+      &::NavParameter::_SpeedLimit_default_instance_);
+}
+inline const ::NavParameter::SpeedLimit& Navigation_parameter::inoutvlimit() const {
+  // @@protoc_insertion_point(field_get:NavParameter.Navigation_parameter.InOutVLimit)
+  return _internal_inoutvlimit();
+}
+inline void Navigation_parameter::unsafe_arena_set_allocated_inoutvlimit(
+    ::NavParameter::SpeedLimit* inoutvlimit) {
+  if (GetArena() == nullptr) {
+    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(inoutvlimit_);
+  }
+  inoutvlimit_ = inoutvlimit;
+  if (inoutvlimit) {
+    
+  } else {
+    
+  }
+  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavParameter.Navigation_parameter.InOutVLimit)
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::release_inoutvlimit() {
+  
+  ::NavParameter::SpeedLimit* temp = inoutvlimit_;
+  inoutvlimit_ = nullptr;
+  if (GetArena() != nullptr) {
+    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
+  }
+  return temp;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::unsafe_arena_release_inoutvlimit() {
+  // @@protoc_insertion_point(field_release:NavParameter.Navigation_parameter.InOutVLimit)
+  
+  ::NavParameter::SpeedLimit* temp = inoutvlimit_;
+  inoutvlimit_ = nullptr;
+  return temp;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::_internal_mutable_inoutvlimit() {
+  
+  if (inoutvlimit_ == nullptr) {
+    auto* p = CreateMaybeMessage<::NavParameter::SpeedLimit>(GetArena());
+    inoutvlimit_ = p;
+  }
+  return inoutvlimit_;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::mutable_inoutvlimit() {
+  // @@protoc_insertion_point(field_mutable:NavParameter.Navigation_parameter.InOutVLimit)
+  return _internal_mutable_inoutvlimit();
+}
+inline void Navigation_parameter::set_allocated_inoutvlimit(::NavParameter::SpeedLimit* inoutvlimit) {
+  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
+  if (message_arena == nullptr) {
+    delete inoutvlimit_;
+  }
+  if (inoutvlimit) {
+    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
+      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(inoutvlimit);
+    if (message_arena != submessage_arena) {
+      inoutvlimit = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
+          message_arena, inoutvlimit, submessage_arena);
+    }
+    
+  } else {
+    
+  }
+  inoutvlimit_ = inoutvlimit;
+  // @@protoc_insertion_point(field_set_allocated:NavParameter.Navigation_parameter.InOutVLimit)
+}
+
+// .NavParameter.SpeedLimit NodeVelocityLimit = 8;
+inline bool Navigation_parameter::_internal_has_nodevelocitylimit() const {
+  return this != internal_default_instance() && nodevelocitylimit_ != nullptr;
+}
+inline bool Navigation_parameter::has_nodevelocitylimit() const {
+  return _internal_has_nodevelocitylimit();
+}
+inline void Navigation_parameter::clear_nodevelocitylimit() {
+  if (GetArena() == nullptr && nodevelocitylimit_ != nullptr) {
+    delete nodevelocitylimit_;
+  }
+  nodevelocitylimit_ = nullptr;
+}
+inline const ::NavParameter::SpeedLimit& Navigation_parameter::_internal_nodevelocitylimit() const {
+  const ::NavParameter::SpeedLimit* p = nodevelocitylimit_;
+  return p != nullptr ? *p : *reinterpret_cast<const ::NavParameter::SpeedLimit*>(
+      &::NavParameter::_SpeedLimit_default_instance_);
+}
+inline const ::NavParameter::SpeedLimit& Navigation_parameter::nodevelocitylimit() const {
+  // @@protoc_insertion_point(field_get:NavParameter.Navigation_parameter.NodeVelocityLimit)
+  return _internal_nodevelocitylimit();
+}
+inline void Navigation_parameter::unsafe_arena_set_allocated_nodevelocitylimit(
+    ::NavParameter::SpeedLimit* nodevelocitylimit) {
+  if (GetArena() == nullptr) {
+    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(nodevelocitylimit_);
+  }
+  nodevelocitylimit_ = nodevelocitylimit;
+  if (nodevelocitylimit) {
+    
+  } else {
+    
+  }
+  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavParameter.Navigation_parameter.NodeVelocityLimit)
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::release_nodevelocitylimit() {
+  
+  ::NavParameter::SpeedLimit* temp = nodevelocitylimit_;
+  nodevelocitylimit_ = nullptr;
+  if (GetArena() != nullptr) {
+    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
+  }
+  return temp;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::unsafe_arena_release_nodevelocitylimit() {
+  // @@protoc_insertion_point(field_release:NavParameter.Navigation_parameter.NodeVelocityLimit)
+  
+  ::NavParameter::SpeedLimit* temp = nodevelocitylimit_;
+  nodevelocitylimit_ = nullptr;
+  return temp;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::_internal_mutable_nodevelocitylimit() {
+  
+  if (nodevelocitylimit_ == nullptr) {
+    auto* p = CreateMaybeMessage<::NavParameter::SpeedLimit>(GetArena());
+    nodevelocitylimit_ = p;
+  }
+  return nodevelocitylimit_;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::mutable_nodevelocitylimit() {
+  // @@protoc_insertion_point(field_mutable:NavParameter.Navigation_parameter.NodeVelocityLimit)
+  return _internal_mutable_nodevelocitylimit();
+}
+inline void Navigation_parameter::set_allocated_nodevelocitylimit(::NavParameter::SpeedLimit* nodevelocitylimit) {
+  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
+  if (message_arena == nullptr) {
+    delete nodevelocitylimit_;
+  }
+  if (nodevelocitylimit) {
+    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
+      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(nodevelocitylimit);
+    if (message_arena != submessage_arena) {
+      nodevelocitylimit = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
+          message_arena, nodevelocitylimit, submessage_arena);
+    }
+    
+  } else {
+    
+  }
+  nodevelocitylimit_ = nodevelocitylimit;
+  // @@protoc_insertion_point(field_set_allocated:NavParameter.Navigation_parameter.NodeVelocityLimit)
+}
+
+// .NavParameter.SpeedLimit NodeAngularLimit = 9;
+inline bool Navigation_parameter::_internal_has_nodeangularlimit() const {
+  return this != internal_default_instance() && nodeangularlimit_ != nullptr;
+}
+inline bool Navigation_parameter::has_nodeangularlimit() const {
+  return _internal_has_nodeangularlimit();
+}
+inline void Navigation_parameter::clear_nodeangularlimit() {
+  if (GetArena() == nullptr && nodeangularlimit_ != nullptr) {
+    delete nodeangularlimit_;
+  }
+  nodeangularlimit_ = nullptr;
+}
+inline const ::NavParameter::SpeedLimit& Navigation_parameter::_internal_nodeangularlimit() const {
+  const ::NavParameter::SpeedLimit* p = nodeangularlimit_;
+  return p != nullptr ? *p : *reinterpret_cast<const ::NavParameter::SpeedLimit*>(
+      &::NavParameter::_SpeedLimit_default_instance_);
+}
+inline const ::NavParameter::SpeedLimit& Navigation_parameter::nodeangularlimit() const {
+  // @@protoc_insertion_point(field_get:NavParameter.Navigation_parameter.NodeAngularLimit)
+  return _internal_nodeangularlimit();
+}
+inline void Navigation_parameter::unsafe_arena_set_allocated_nodeangularlimit(
+    ::NavParameter::SpeedLimit* nodeangularlimit) {
+  if (GetArena() == nullptr) {
+    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(nodeangularlimit_);
+  }
+  nodeangularlimit_ = nodeangularlimit;
+  if (nodeangularlimit) {
+    
+  } else {
+    
+  }
+  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavParameter.Navigation_parameter.NodeAngularLimit)
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::release_nodeangularlimit() {
+  
+  ::NavParameter::SpeedLimit* temp = nodeangularlimit_;
+  nodeangularlimit_ = nullptr;
+  if (GetArena() != nullptr) {
+    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
+  }
+  return temp;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::unsafe_arena_release_nodeangularlimit() {
+  // @@protoc_insertion_point(field_release:NavParameter.Navigation_parameter.NodeAngularLimit)
+  
+  ::NavParameter::SpeedLimit* temp = nodeangularlimit_;
+  nodeangularlimit_ = nullptr;
+  return temp;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::_internal_mutable_nodeangularlimit() {
+  
+  if (nodeangularlimit_ == nullptr) {
+    auto* p = CreateMaybeMessage<::NavParameter::SpeedLimit>(GetArena());
+    nodeangularlimit_ = p;
+  }
+  return nodeangularlimit_;
+}
+inline ::NavParameter::SpeedLimit* Navigation_parameter::mutable_nodeangularlimit() {
+  // @@protoc_insertion_point(field_mutable:NavParameter.Navigation_parameter.NodeAngularLimit)
+  return _internal_mutable_nodeangularlimit();
+}
+inline void Navigation_parameter::set_allocated_nodeangularlimit(::NavParameter::SpeedLimit* nodeangularlimit) {
+  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
+  if (message_arena == nullptr) {
+    delete nodeangularlimit_;
+  }
+  if (nodeangularlimit) {
+    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
+      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(nodeangularlimit);
+    if (message_arena != submessage_arena) {
+      nodeangularlimit = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
+          message_arena, nodeangularlimit, submessage_arena);
+    }
+    
+  } else {
+    
+  }
+  nodeangularlimit_ = nodeangularlimit;
+  // @@protoc_insertion_point(field_set_allocated:NavParameter.Navigation_parameter.NodeAngularLimit)
+}
+
 #ifdef __GNUC__
   #pragma GCC diagnostic pop
 #endif  // __GNUC__
@@ -2551,6 +3252,10 @@ inline void Navigation_parameter::set_allocated_y_mpc_parameter(::NavParameter::
 
 // -------------------------------------------------------------------
 
+// -------------------------------------------------------------------
+
+// -------------------------------------------------------------------
+
 
 // @@protoc_insertion_point(namespace_scope)
 

+ 1 - 1
MPC/pose2d.h

@@ -83,7 +83,7 @@ class Pose2d
 
     bool operator<=(const Pose2d& target)const
     {
-      return x()<=target.x() && y()<target.y() && theta()<target.theta();
+      return x()<=target.x() && y()<=target.y() && theta()<=target.theta();
     }
 
     /*

+ 18 - 1
config/navigation.prototxt

@@ -27,7 +27,7 @@ brother_emqx
 	NodeId:"agv-child"
 	ip:"192.168.0.70"
 	port:1883
-	subBrotherStatuTopic:"monitor_child/statu"
+	subBrotherStatuTopic:"agv_main/nav_statu"
 }
 
 x_mpc_parameter
@@ -44,3 +44,20 @@ y_mpc_parameter
 	acc_velocity:1.5
 	acc_angular:10
 }
+
+
+InOutVLimit
+{
+    min:0.03
+    max:0.5
+}
+NodeVelocityLimit
+{
+    min:0.03
+    max:1.5
+}
+NodeAngularLimit
+{
+    min:0.0523
+    max:0.4
+}

+ 17 - 1
config/navigation_main.prototxt

@@ -26,7 +26,7 @@ brother_emqx
 	NodeId:"agv-main"
 	ip:"192.168.0.71"
 	port:1883
-	subBrotherStatuTopic:"monitor_child/statu"
+	subBrotherStatuTopic:"agv_child/nav_statu"
 }
 
 x_mpc_parameter
@@ -43,3 +43,19 @@ y_mpc_parameter
 	acc_velocity:1.0
 	acc_angular:10
 }
+
+InOutVLimit
+{
+    min:0.03
+    max:0.5
+}
+NodeVelocityLimit
+{
+    min:0.03
+    max:1.5
+}
+NodeAngularLimit
+{
+    min:0.0523
+    max:0.4
+}

+ 20 - 0
config/webots/navigation.prototxt

@@ -44,3 +44,23 @@ y_mpc_parameter
 	acc_velocity:1.0
 	acc_angular:10
 }
+
+InOutVLimit
+{
+    min:0.03
+    max:0.5
+}
+NodeVelocityLimit
+{
+    min:0.03
+    max:1.5
+}
+NodeAngularLimit
+{
+    min:0.0523
+    max:0.4
+}
+
+
+
+

+ 17 - 0
config/webots/navigation_main.prototxt

@@ -43,3 +43,20 @@ y_mpc_parameter
 	acc_velocity:1.0
 	acc_angular:10
 }
+
+InOutVLimit
+{
+    min:0.03
+    max:0.5
+}
+NodeVelocityLimit
+{
+    min:0.03
+    max:1.5
+}
+NodeAngularLimit
+{
+    min:0.0523
+    max:0.4
+}
+

+ 3 - 13
message.proto

@@ -26,12 +26,6 @@ message ToAgvCmd {
   int32 end=7;
 }
 
-message SpeedLimit
-{
-  float min=1;
-  float max=2;
-}
-
 message Pose2d
 {
   float x=1;
@@ -62,13 +56,9 @@ message NewAction //进库,出库,轨迹导航,夹持,松夹持
   PathNode passNode=3; //进出库途径点
   PathNode streetNode = 4; //进出库终点
   repeated PathNode pathNodes=5;//导航路径点
-  SpeedLimit InOutVLimit=6; //进出库速度
-  SpeedLimit NodeVelocityLimit=7; //马路点MPC速度限制
-  SpeedLimit NodeAngularLimit=8;  //马路点原地旋转速度限制
-  SpeedLimit adjustVelocitylimit=9; //马路点原地调整x速度
-  SpeedLimit adjustHorizonLimit=10;  //马路点原地横移速度限制
-  float wheelbase=11;		//切换模式,轴距信息
-  int32 changedMode=12; //1:切换单车模式,2:切换双车模式
+
+  float wheelbase=6;		//切换模式,轴距信息
+  int32 changedMode=7; //1:切换单车模式,2:切换双车模式
 }
 //-----------------------------
 

+ 14 - 0
parameter.proto

@@ -34,6 +34,16 @@ message MPC_parameter
   float acc_angular=4;
 }
 
+message SpeedLimit{
+  float min=1;
+  float max=2;
+}
+
+message Accuracy{
+  float l=1;
+  float w=2;
+}
+
 message Navigation_parameter
 {
   bool main_agv=1;   //是否是两车整体
@@ -42,5 +52,9 @@ message Navigation_parameter
     BrotherEmqx brother_emqx=4;
     MPC_parameter x_mpc_parameter=5;
     MPC_parameter y_mpc_parameter=6;
+
+  SpeedLimit InOutVLimit=7; //进出库速度
+  SpeedLimit NodeVelocityLimit=8; //马路点MPC速度限制
+  SpeedLimit NodeAngularLimit=9;  //马路点原地旋转速度限制
 }