Procházet zdrojové kódy

主cpu速度指令增加L轴距信息

zx před 2 roky
rodič
revize
e9e977e07d

+ 87 - 84
MPC/monitor/emqx/message.pb.cc

@@ -111,9 +111,8 @@ static void InitDefaultsscc_info_NavCmd_message_2eproto() {
   ::NavMessage::NavCmd::InitAsDefaultInstance();
 }
 
-::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<2> scc_info_NavCmd_message_2eproto =
-    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 2, 0, InitDefaultsscc_info_NavCmd_message_2eproto}, {
-      &scc_info_Pose2d_message_2eproto.base,
+::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<1> scc_info_NavCmd_message_2eproto =
+    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 1, 0, InitDefaultsscc_info_NavCmd_message_2eproto}, {
       &scc_info_Action_message_2eproto.base,}};
 
 static void InitDefaultsscc_info_NavStatu_message_2eproto() {
@@ -221,6 +220,7 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_message_2eproto::offsets[] PRO
   PROTOBUF_FIELD_OFFSET(::NavMessage::Speed, t_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::Speed, v_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::Speed, w_),
+  PROTOBUF_FIELD_OFFSET(::NavMessage::Speed, l_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::Speed, end_),
   ~0u,  // no _has_bits_
   PROTOBUF_FIELD_OFFSET(::NavMessage::SpeedLimit, _internal_metadata_),
@@ -262,7 +262,7 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_message_2eproto::offsets[] PRO
   ~0u,  // no _weak_field_map_
   PROTOBUF_FIELD_OFFSET(::NavMessage::NavCmd, action_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::NavCmd, key_),
-  PROTOBUF_FIELD_OFFSET(::NavMessage::NavCmd, transform_),
+  PROTOBUF_FIELD_OFFSET(::NavMessage::NavCmd, wheelbase_),
   PROTOBUF_FIELD_OFFSET(::NavMessage::NavCmd, actions_),
   ~0u,  // no _has_bits_
   PROTOBUF_FIELD_OFFSET(::NavMessage::NavStatu, _internal_metadata_),
@@ -281,12 +281,12 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB
   { 0, -1, sizeof(::NavMessage::AGVStatu)},
   { 10, -1, sizeof(::NavMessage::AGVSpeed)},
   { 17, -1, sizeof(::NavMessage::Speed)},
-  { 28, -1, sizeof(::NavMessage::SpeedLimit)},
-  { 35, -1, sizeof(::NavMessage::Pose2d)},
-  { 43, -1, sizeof(::NavMessage::Trajectory)},
-  { 49, -1, sizeof(::NavMessage::Action)},
-  { 61, -1, sizeof(::NavMessage::NavCmd)},
-  { 70, -1, sizeof(::NavMessage::NavStatu)},
+  { 29, -1, sizeof(::NavMessage::SpeedLimit)},
+  { 36, -1, sizeof(::NavMessage::Pose2d)},
+  { 44, -1, sizeof(::NavMessage::Trajectory)},
+  { 50, -1, sizeof(::NavMessage::Action)},
+  { 62, -1, sizeof(::NavMessage::NavCmd)},
+  { 71, -1, sizeof(::NavMessage::NavStatu)},
 };
 
 static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = {
@@ -305,28 +305,27 @@ const char descriptor_table_protodef_message_2eproto[] PROTOBUF_SECTION_VARIABLE
   "\n\rmessage.proto\022\nNavMessage\"G\n\010AGVStatu\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\t\n\001"
   "v\030\004 \001(\002\022\013\n\003vth\030\005 \001(\002\" \n\010AGVSpeed\022\t\n\001v\030\001 "
-  "\001(\002\022\t\n\001w\030\002 \001(\002\"K\n\005Speed\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\013"
-  "\n\003end\030\006 \001(\005\"&\n\nSpeedLimit\022\013\n\003min\030\001 \001(\002\022\013"
-  "\n\003max\030\002 \001(\002\"-\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\"/\n\nTrajectory\022!\n\005pose"
-  "s\030\001 \003(\0132\022.NavMessage.Pose2d\"\223\002\n\006Action\022\014"
-  "\n\004type\030\001 \001(\005\022!\n\005begin\030\002 \001(\0132\022.NavMessage"
-  ".Pose2d\022\"\n\006target\030\003 \001(\0132\022.NavMessage.Pos"
-  "e2d\022\'\n\013target_diff\030\004 \001(\0132\022.NavMessage.Po"
-  "se2d\022.\n\016velocity_limit\030\005 \001(\0132\026.NavMessag"
-  "e.SpeedLimit\022-\n\rangular_limit\030\006 \001(\0132\026.Na"
-  "vMessage.SpeedLimit\022,\n\014horize_limit\030\007 \001("
-  "\0132\026.NavMessage.SpeedLimit\"q\n\006NavCmd\022\016\n\006a"
-  "ction\030\001 \001(\005\022\013\n\003key\030\002 \001(\t\022%\n\ttransform\030\003 "
-  "\001(\0132\022.NavMessage.Pose2d\022#\n\007actions\030\004 \003(\013"
-  "2\022.NavMessage.Action\"\330\001\n\010NavStatu\022\r\n\005sta"
-  "tu\030\001 \001(\010\022\020\n\010main_agv\030\002 \001(\010\022\021\n\tmove_mode\030"
-  "\003 \001(\005\022\013\n\003key\030\004 \001(\t\022.\n\022unfinished_actions"
-  "\030\005 \003(\0132\022.NavMessage.Action\022-\n\rselected_t"
-  "raj\030\006 \001(\0132\026.NavMessage.Trajectory\022,\n\014pre"
-  "dict_traj\030\007 \001(\0132\026.NavMessage.Trajectoryb"
-  "\006proto3"
+  "\001(\002\022\t\n\001w\030\002 \001(\002\"V\n\005Speed\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\nSpeedLimit\022\013\n\003"
+  "min\030\001 \001(\002\022\013\n\003max\030\002 \001(\002\"-\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\"/\n\nTraject"
+  "ory\022!\n\005poses\030\001 \003(\0132\022.NavMessage.Pose2d\"\223"
+  "\002\n\006Action\022\014\n\004type\030\001 \001(\005\022!\n\005begin\030\002 \001(\0132\022"
+  ".NavMessage.Pose2d\022\"\n\006target\030\003 \001(\0132\022.Nav"
+  "Message.Pose2d\022\'\n\013target_diff\030\004 \001(\0132\022.Na"
+  "vMessage.Pose2d\022.\n\016velocity_limit\030\005 \001(\0132"
+  "\026.NavMessage.SpeedLimit\022-\n\rangular_limit"
+  "\030\006 \001(\0132\026.NavMessage.SpeedLimit\022,\n\014horize"
+  "_limit\030\007 \001(\0132\026.NavMessage.SpeedLimit\"]\n\006"
+  "NavCmd\022\016\n\006action\030\001 \001(\005\022\013\n\003key\030\002 \001(\t\022\021\n\tw"
+  "heelbase\030\003 \001(\002\022#\n\007actions\030\004 \003(\0132\022.NavMes"
+  "sage.Action\"\330\001\n\010NavStatu\022\r\n\005statu\030\001 \001(\010\022"
+  "\020\n\010main_agv\030\002 \001(\010\022\021\n\tmove_mode\030\003 \001(\005\022\013\n\003"
+  "key\030\004 \001(\t\022.\n\022unfinished_actions\030\005 \003(\0132\022."
+  "NavMessage.Action\022-\n\rselected_traj\030\006 \001(\013"
+  "2\026.NavMessage.Trajectory\022,\n\014predict_traj"
+  "\030\007 \001(\0132\026.NavMessage.Trajectoryb\006proto3"
   ;
 static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_message_2eproto_deps[1] = {
 };
@@ -343,7 +342,7 @@ static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_mes
 };
 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", 967,
+  false, false, descriptor_table_protodef_message_2eproto, "message.proto", 958,
   &descriptor_table_message_2eproto_once, descriptor_table_message_2eproto_sccs, descriptor_table_message_2eproto_deps, 9, 0,
   schemas, file_default_instances, TableStruct_message_2eproto::offsets,
   file_level_metadata_message_2eproto, 9, file_level_enum_descriptors_message_2eproto, file_level_service_descriptors_message_2eproto,
@@ -979,9 +978,16 @@ const char* Speed::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::inte
           ptr += sizeof(float);
         } else goto handle_unusual;
         continue;
-      // int32 end = 6;
+      // float L = 6;
       case 6:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 48)) {
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 53)) {
+          l_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // int32 end = 7;
+      case 7:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 56)) {
           end_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
           CHK_(ptr);
         } else goto handle_unusual;
@@ -1044,10 +1050,16 @@ failure:
     target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(5, this->_internal_w(), target);
   }
 
-  // int32 end = 6;
+  // float L = 6;
+  if (!(this->l() <= 0 && this->l() >= 0)) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(6, this->_internal_l(), target);
+  }
+
+  // int32 end = 7;
   if (this->end() != 0) {
     target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(6, this->_internal_end(), target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(7, this->_internal_end(), target);
   }
 
   if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
@@ -1097,7 +1109,12 @@ size_t Speed::ByteSizeLong() const {
     total_size += 1 + 4;
   }
 
-  // int32 end = 6;
+  // float L = 6;
+  if (!(this->l() <= 0 && this->l() >= 0)) {
+    total_size += 1 + 4;
+  }
+
+  // int32 end = 7;
   if (this->end() != 0) {
     total_size += 1 +
       ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
@@ -1150,6 +1167,9 @@ void Speed::MergeFrom(const Speed& from) {
   if (!(from.w() <= 0 && from.w() >= 0)) {
     _internal_set_w(from._internal_w());
   }
+  if (!(from.l() <= 0 && from.l() >= 0)) {
+    _internal_set_l(from._internal_l());
+  }
   if (from.end() != 0) {
     _internal_set_end(from._internal_end());
   }
@@ -2327,18 +2347,11 @@ void Action::InternalSwap(Action* other) {
 // ===================================================================
 
 void NavCmd::InitAsDefaultInstance() {
-  ::NavMessage::_NavCmd_default_instance_._instance.get_mutable()->transform_ = const_cast< ::NavMessage::Pose2d*>(
-      ::NavMessage::Pose2d::internal_default_instance());
 }
 class NavCmd::_Internal {
  public:
-  static const ::NavMessage::Pose2d& transform(const NavCmd* msg);
 };
 
-const ::NavMessage::Pose2d&
-NavCmd::_Internal::transform(const NavCmd* msg) {
-  return *msg->transform_;
-}
 NavCmd::NavCmd(::PROTOBUF_NAMESPACE_ID::Arena* arena)
   : ::PROTOBUF_NAMESPACE_ID::Message(arena),
   actions_(arena) {
@@ -2355,21 +2368,18 @@ NavCmd::NavCmd(const NavCmd& from)
     key_.Set(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), from._internal_key(),
       GetArena());
   }
-  if (from._internal_has_transform()) {
-    transform_ = new ::NavMessage::Pose2d(*from.transform_);
-  } else {
-    transform_ = nullptr;
-  }
-  action_ = from.action_;
+  ::memcpy(&action_, &from.action_,
+    static_cast<size_t>(reinterpret_cast<char*>(&wheelbase_) -
+    reinterpret_cast<char*>(&action_)) + sizeof(wheelbase_));
   // @@protoc_insertion_point(copy_constructor:NavMessage.NavCmd)
 }
 
 void NavCmd::SharedCtor() {
   ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&scc_info_NavCmd_message_2eproto.base);
   key_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited());
-  ::memset(&transform_, 0, static_cast<size_t>(
-      reinterpret_cast<char*>(&action_) -
-      reinterpret_cast<char*>(&transform_)) + sizeof(action_));
+  ::memset(&action_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&wheelbase_) -
+      reinterpret_cast<char*>(&action_)) + sizeof(wheelbase_));
 }
 
 NavCmd::~NavCmd() {
@@ -2381,7 +2391,6 @@ NavCmd::~NavCmd() {
 void NavCmd::SharedDtor() {
   GOOGLE_DCHECK(GetArena() == nullptr);
   key_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited());
-  if (this != internal_default_instance()) delete transform_;
 }
 
 void NavCmd::ArenaDtor(void* object) {
@@ -2407,11 +2416,9 @@ void NavCmd::Clear() {
 
   actions_.Clear();
   key_.ClearToEmpty(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArena());
-  if (GetArena() == nullptr && transform_ != nullptr) {
-    delete transform_;
-  }
-  transform_ = nullptr;
-  action_ = 0;
+  ::memset(&action_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&wheelbase_) -
+      reinterpret_cast<char*>(&action_)) + sizeof(wheelbase_));
   _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
 }
 
@@ -2439,11 +2446,11 @@ const char* NavCmd::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::int
           CHK_(ptr);
         } else goto handle_unusual;
         continue;
-      // .NavMessage.Pose2d transform = 3;
+      // float wheelbase = 3;
       case 3:
-        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 26)) {
-          ptr = ctx->ParseMessage(_internal_mutable_transform(), ptr);
-          CHK_(ptr);
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 29)) {
+          wheelbase_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
         } else goto handle_unusual;
         continue;
       // repeated .NavMessage.Action actions = 4;
@@ -2502,12 +2509,10 @@ failure:
         2, this->_internal_key(), target);
   }
 
-  // .NavMessage.Pose2d transform = 3;
-  if (this->has_transform()) {
+  // float wheelbase = 3;
+  if (!(this->wheelbase() <= 0 && this->wheelbase() >= 0)) {
     target = stream->EnsureSpace(target);
-    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::
-      InternalWriteMessage(
-        3, _Internal::transform(this), target, stream);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(3, this->_internal_wheelbase(), target);
   }
 
   // repeated .NavMessage.Action actions = 4;
@@ -2548,13 +2553,6 @@ size_t NavCmd::ByteSizeLong() const {
         this->_internal_key());
   }
 
-  // .NavMessage.Pose2d transform = 3;
-  if (this->has_transform()) {
-    total_size += 1 +
-      ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(
-        *transform_);
-  }
-
   // int32 action = 1;
   if (this->action() != 0) {
     total_size += 1 +
@@ -2562,6 +2560,11 @@ size_t NavCmd::ByteSizeLong() const {
         this->_internal_action());
   }
 
+  // float wheelbase = 3;
+  if (!(this->wheelbase() <= 0 && this->wheelbase() >= 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_);
@@ -2597,12 +2600,12 @@ void NavCmd::MergeFrom(const NavCmd& from) {
   if (from.key().size() > 0) {
     _internal_set_key(from._internal_key());
   }
-  if (from.has_transform()) {
-    _internal_mutable_transform()->::NavMessage::Pose2d::MergeFrom(from._internal_transform());
-  }
   if (from.action() != 0) {
     _internal_set_action(from._internal_action());
   }
+  if (!(from.wheelbase() <= 0 && from.wheelbase() >= 0)) {
+    _internal_set_wheelbase(from._internal_wheelbase());
+  }
 }
 
 void NavCmd::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
@@ -2629,11 +2632,11 @@ void NavCmd::InternalSwap(NavCmd* other) {
   actions_.InternalSwap(&other->actions_);
   key_.Swap(&other->key_, &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArena());
   ::PROTOBUF_NAMESPACE_ID::internal::memswap<
-      PROTOBUF_FIELD_OFFSET(NavCmd, action_)
-      + sizeof(NavCmd::action_)
-      - PROTOBUF_FIELD_OFFSET(NavCmd, transform_)>(
-          reinterpret_cast<char*>(&transform_),
-          reinterpret_cast<char*>(&other->transform_));
+      PROTOBUF_FIELD_OFFSET(NavCmd, wheelbase_)
+      + sizeof(NavCmd::wheelbase_)
+      - PROTOBUF_FIELD_OFFSET(NavCmd, action_)>(
+          reinterpret_cast<char*>(&action_),
+          reinterpret_cast<char*>(&other->action_));
 }
 
 ::PROTOBUF_NAMESPACE_ID::Metadata NavCmd::GetMetadata() const {

+ 58 - 99
MPC/monitor/emqx/message.pb.h

@@ -545,7 +545,8 @@ class Speed PROTOBUF_FINAL :
     kTFieldNumber = 3,
     kVFieldNumber = 4,
     kWFieldNumber = 5,
-    kEndFieldNumber = 6,
+    kLFieldNumber = 6,
+    kEndFieldNumber = 7,
   };
   // int32 H = 1;
   void clear_h();
@@ -592,7 +593,16 @@ class Speed PROTOBUF_FINAL :
   void _internal_set_w(float value);
   public:
 
-  // int32 end = 6;
+  // float L = 6;
+  void clear_l();
+  float l() const;
+  void set_l(float value);
+  private:
+  float _internal_l() const;
+  void _internal_set_l(float value);
+  public:
+
+  // int32 end = 7;
   void clear_end();
   ::PROTOBUF_NAMESPACE_ID::int32 end() const;
   void set_end(::PROTOBUF_NAMESPACE_ID::int32 value);
@@ -613,6 +623,7 @@ class Speed PROTOBUF_FINAL :
   ::PROTOBUF_NAMESPACE_ID::int32 t_;
   float v_;
   float w_;
+  float l_;
   ::PROTOBUF_NAMESPACE_ID::int32 end_;
   mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
   friend struct ::TableStruct_message_2eproto;
@@ -1444,8 +1455,8 @@ class NavCmd PROTOBUF_FINAL :
   enum : int {
     kActionsFieldNumber = 4,
     kKeyFieldNumber = 2,
-    kTransformFieldNumber = 3,
     kActionFieldNumber = 1,
+    kWheelbaseFieldNumber = 3,
   };
   // repeated .NavMessage.Action actions = 4;
   int actions_size() const;
@@ -1481,24 +1492,6 @@ class NavCmd PROTOBUF_FINAL :
   std::string* _internal_mutable_key();
   public:
 
-  // .NavMessage.Pose2d transform = 3;
-  bool has_transform() const;
-  private:
-  bool _internal_has_transform() const;
-  public:
-  void clear_transform();
-  const ::NavMessage::Pose2d& transform() const;
-  ::NavMessage::Pose2d* release_transform();
-  ::NavMessage::Pose2d* mutable_transform();
-  void set_allocated_transform(::NavMessage::Pose2d* transform);
-  private:
-  const ::NavMessage::Pose2d& _internal_transform() const;
-  ::NavMessage::Pose2d* _internal_mutable_transform();
-  public:
-  void unsafe_arena_set_allocated_transform(
-      ::NavMessage::Pose2d* transform);
-  ::NavMessage::Pose2d* unsafe_arena_release_transform();
-
   // int32 action = 1;
   void clear_action();
   ::PROTOBUF_NAMESPACE_ID::int32 action() const;
@@ -1508,6 +1501,15 @@ class NavCmd PROTOBUF_FINAL :
   void _internal_set_action(::PROTOBUF_NAMESPACE_ID::int32 value);
   public:
 
+  // float wheelbase = 3;
+  void clear_wheelbase();
+  float wheelbase() const;
+  void set_wheelbase(float value);
+  private:
+  float _internal_wheelbase() const;
+  void _internal_set_wheelbase(float value);
+  public:
+
   // @@protoc_insertion_point(class_scope:NavMessage.NavCmd)
  private:
   class _Internal;
@@ -1517,8 +1519,8 @@ class NavCmd PROTOBUF_FINAL :
   typedef void DestructorSkippable_;
   ::PROTOBUF_NAMESPACE_ID::RepeatedPtrField< ::NavMessage::Action > actions_;
   ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr key_;
-  ::NavMessage::Pose2d* transform_;
   ::PROTOBUF_NAMESPACE_ID::int32 action_;
+  float wheelbase_;
   mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
   friend struct ::TableStruct_message_2eproto;
 };
@@ -2018,7 +2020,27 @@ inline void Speed::set_w(float value) {
   // @@protoc_insertion_point(field_set:NavMessage.Speed.W)
 }
 
-// int32 end = 6;
+// float L = 6;
+inline void Speed::clear_l() {
+  l_ = 0;
+}
+inline float Speed::_internal_l() const {
+  return l_;
+}
+inline float Speed::l() const {
+  // @@protoc_insertion_point(field_get:NavMessage.Speed.L)
+  return _internal_l();
+}
+inline void Speed::_internal_set_l(float value) {
+  
+  l_ = value;
+}
+inline void Speed::set_l(float value) {
+  _internal_set_l(value);
+  // @@protoc_insertion_point(field_set:NavMessage.Speed.L)
+}
+
+// int32 end = 7;
 inline void Speed::clear_end() {
   end_ = 0;
 }
@@ -2797,87 +2819,24 @@ inline void NavCmd::set_allocated_key(std::string* key) {
   // @@protoc_insertion_point(field_set_allocated:NavMessage.NavCmd.key)
 }
 
-// .NavMessage.Pose2d transform = 3;
-inline bool NavCmd::_internal_has_transform() const {
-  return this != internal_default_instance() && transform_ != nullptr;
-}
-inline bool NavCmd::has_transform() const {
-  return _internal_has_transform();
-}
-inline void NavCmd::clear_transform() {
-  if (GetArena() == nullptr && transform_ != nullptr) {
-    delete transform_;
-  }
-  transform_ = nullptr;
-}
-inline const ::NavMessage::Pose2d& NavCmd::_internal_transform() const {
-  const ::NavMessage::Pose2d* p = transform_;
-  return p != nullptr ? *p : *reinterpret_cast<const ::NavMessage::Pose2d*>(
-      &::NavMessage::_Pose2d_default_instance_);
-}
-inline const ::NavMessage::Pose2d& NavCmd::transform() const {
-  // @@protoc_insertion_point(field_get:NavMessage.NavCmd.transform)
-  return _internal_transform();
-}
-inline void NavCmd::unsafe_arena_set_allocated_transform(
-    ::NavMessage::Pose2d* transform) {
-  if (GetArena() == nullptr) {
-    delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(transform_);
-  }
-  transform_ = transform;
-  if (transform) {
-    
-  } else {
-    
-  }
-  // @@protoc_insertion_point(field_unsafe_arena_set_allocated:NavMessage.NavCmd.transform)
+// float wheelbase = 3;
+inline void NavCmd::clear_wheelbase() {
+  wheelbase_ = 0;
 }
-inline ::NavMessage::Pose2d* NavCmd::release_transform() {
-  
-  ::NavMessage::Pose2d* temp = transform_;
-  transform_ = nullptr;
-  if (GetArena() != nullptr) {
-    temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp);
-  }
-  return temp;
+inline float NavCmd::_internal_wheelbase() const {
+  return wheelbase_;
 }
-inline ::NavMessage::Pose2d* NavCmd::unsafe_arena_release_transform() {
-  // @@protoc_insertion_point(field_release:NavMessage.NavCmd.transform)
-  
-  ::NavMessage::Pose2d* temp = transform_;
-  transform_ = nullptr;
-  return temp;
+inline float NavCmd::wheelbase() const {
+  // @@protoc_insertion_point(field_get:NavMessage.NavCmd.wheelbase)
+  return _internal_wheelbase();
 }
-inline ::NavMessage::Pose2d* NavCmd::_internal_mutable_transform() {
+inline void NavCmd::_internal_set_wheelbase(float value) {
   
-  if (transform_ == nullptr) {
-    auto* p = CreateMaybeMessage<::NavMessage::Pose2d>(GetArena());
-    transform_ = p;
-  }
-  return transform_;
+  wheelbase_ = value;
 }
-inline ::NavMessage::Pose2d* NavCmd::mutable_transform() {
-  // @@protoc_insertion_point(field_mutable:NavMessage.NavCmd.transform)
-  return _internal_mutable_transform();
-}
-inline void NavCmd::set_allocated_transform(::NavMessage::Pose2d* transform) {
-  ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArena();
-  if (message_arena == nullptr) {
-    delete transform_;
-  }
-  if (transform) {
-    ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena =
-      ::PROTOBUF_NAMESPACE_ID::Arena::GetArena(transform);
-    if (message_arena != submessage_arena) {
-      transform = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage(
-          message_arena, transform, submessage_arena);
-    }
-    
-  } else {
-    
-  }
-  transform_ = transform;
-  // @@protoc_insertion_point(field_set_allocated:NavMessage.NavCmd.transform)
+inline void NavCmd::set_wheelbase(float value) {
+  _internal_set_wheelbase(value);
+  // @@protoc_insertion_point(field_set:NavMessage.NavCmd.wheelbase)
 }
 
 // repeated .NavMessage.Action actions = 4;

+ 23 - 2
MPC/monitor/monitor_emqx.cpp

@@ -24,9 +24,13 @@ void Monitor_emqx::set_speedcmd_topic(std::string speedcmd)
   speedcmd_topic_=speedcmd;
 }
 
-void Monitor_emqx::set_speed(MoveMode mode,SpeedType type,double v,double a)
+void Monitor_emqx::set_speed(MoveMode mode,SpeedType type,double v,double a,double L)
 {
-
+  if(mode==eMain && type==eMPC &&fabs(L)<1e-3)
+  {
+    printf(" Main agv mpc must set wheelBase\n ");
+    return;
+  }
   double w=fabs(a)>0.001?a:0.0;
   MqttMsg msg;
   NavMessage::Speed speed;
@@ -35,12 +39,29 @@ void Monitor_emqx::set_speed(MoveMode mode,SpeedType type,double v,double a)
   speed.set_t(type);
   speed.set_v(v);
   speed.set_w(w);
+  speed.set_l(L);
 
   speed.set_m(mode);
   speed.set_end(1);
   msg.fromProtoMessage(speed);
   Publish(speedcmd_topic_,msg);
 
+}
+void Monitor_emqx::set_speed(MoveMode mode,SpeedType type,double v,double a)
+{
+  double w=fabs(a)>0.001?a:0.0;
+  MqttMsg msg;
+  NavMessage::Speed speed;
+  heat_=(heat_+1)%255;
+  speed.set_h(heat_);
+  speed.set_t(type);
+  speed.set_v(v);
+  speed.set_w(w);
+  speed.set_m(mode);
+  speed.set_end(1);
+  msg.fromProtoMessage(speed);
+  Publish(speedcmd_topic_,msg);
+
 }
 
 void Monitor_emqx::stop()

+ 1 - 0
MPC/monitor/monitor_emqx.h

@@ -29,6 +29,7 @@ public:
     ~Monitor_emqx();
     void set_speedcmd_topic(std::string speedcmd);
     void set_speed(MoveMode mode,SpeedType type,double v,double a);
+    void set_speed(MoveMode mode,SpeedType type,double v,double a,double L);
     void stop();
 
  protected:

+ 22 - 5
MPC/navigation_main.cpp

@@ -7,14 +7,17 @@
 
 NavigationMain::NavigationMain(){
   move_mode_=Monitor_emqx::eSingle;
+  wheelBase_=0;
 }
 NavigationMain::~NavigationMain(){
 
 }
 
 void NavigationMain::ResetPose(const Pose2d& pose){
-  if(move_mode_==Monitor_emqx::eMain)
-    Navigation::ResetPose(pose*transform_);
+  if(move_mode_==Monitor_emqx::eMain) {
+    Pose2d transform(-wheelBase_/2.0,0,0);
+    Navigation::ResetPose(pose * transform);
+  }
   else
     Navigation::ResetPose(pose);
 }
@@ -29,15 +32,19 @@ void NavigationMain::HandleNavCmd(const NavMessage::NavCmd& cmd)
 {
   if(cmd.action()==4)
   {
+    if(cmd.wheelbase()<2.4 || cmd.wheelbase()>3.5)
+    {
+      printf("Failed to Switch MoveMode --> main,wheelbase invalid :%f\n",cmd.wheelbase());
+      return;
+    }
     printf(" Switch MoveMode --> main\n");
-    NavMessage::Pose2d transform=cmd.transform();
-    SwitchMode(Monitor_emqx::eMain,Pose2d(transform.x(),transform.y(),transform.theta()));
+    SwitchMode(Monitor_emqx::eMain,cmd.wheelbase());
     return ;
   }
   if(cmd.action()==5)
   {
     printf(" Switch MoveMode --> single\n");
-    SwitchMode(Monitor_emqx::eSingle,Pose2d());
+    SwitchMode(Monitor_emqx::eSingle,0);
     return ;
   }
   else
@@ -56,4 +63,14 @@ bool NavigationMain::Start(const NavMessage::NavCmd& cmd)
 
   return Navigation::Start(cmd);
 
+}
+
+void NavigationMain::SendMoveCmd(Monitor_emqx::MoveMode mode,Monitor_emqx::SpeedType type,
+                double v,double angular)
+{
+  if(monitor_)
+  {
+    monitor_->set_speed(mode,type,v,angular,wheelBase_);
+  }
+
 }

+ 7 - 3
MPC/navigation_main.h

@@ -14,17 +14,21 @@ public:
     virtual void ResetPose(const Pose2d& pose);
     virtual bool Start(const NavMessage::NavCmd& cmd);
     virtual void publish_statu(NavMessage::NavStatu& statu);
-    virtual void SwitchMode(Monitor_emqx::MoveMode mode,const Pose2d& transform){
+    virtual void SwitchMode(Monitor_emqx::MoveMode mode,float wheelBase){
       move_mode_=mode;
       if(move_mode_==Monitor_emqx::eMain)
       {
-        transform_=transform;
+        wheelBase_=wheelBase;
       }
     }
+
+
 protected:
+    virtual void SendMoveCmd(Monitor_emqx::MoveMode mode,Monitor_emqx::SpeedType type,
+                             double v,double angular);
     virtual void HandleNavCmd(const NavMessage::NavCmd& cmd);
 protected:
-    Pose2d  transform_;   //两节agv的位姿与单节的位姿变换
+    float  wheelBase_;   //两节agv的位姿与单节的位姿变换
 };
 
 #endif //NAVIGATION_NAVIGATION_MAIN_H

+ 2 - 2
config/navigation_child.prototxt

@@ -3,7 +3,7 @@ main_agv:true
 Agv_emqx
 {
 	NodeId:"agv-child"
-	ip:"127.0.0.1"
+	ip:"192.168.0.70"
 	port:1883
 	pubSpeedTopic:"monitor_child/speedcmd"
 	subPoseTopic:"monitor_child/statu"
@@ -13,7 +13,7 @@ Agv_emqx
 Terminal_emqx
 {
 	NodeId:"agv1-child-nav"
-	ip:"127.0.0.1"
+	ip:"192.168.0.70"
 	port:1883
 	pubStatuTopic:"agv1_child/agv_statu"
 	pubNavStatuTopic:"agv1_child/nav_statu"

+ 3 - 2
message.proto

@@ -19,7 +19,8 @@ message Speed {
   int32 T=3; // 1:原地旋转,2:横移,3:MPC巡线/前进, 其他/未接收到:停止
   float V=4;  //角速度
   float W=5;  //线速度
-  int32 end=6;
+  float L=6;  //轴距
+  int32 end=7;
 }
 
 message SpeedLimit
@@ -56,7 +57,7 @@ message NavCmd
 {
   int32 action=1;  //  0 开始导航,1 pause, 2 continue ,3 cancel,4:切换到双车模式,5:切换到单车模式
   string key=2;
-  Pose2d transform=3;		//整车中心与单节的变换
+  float wheelbase=3;		//轴距
   repeated Action actions=4;
 }