// Generated by gencpp from file unitree_legged_msgs/LowState.msg // DO NOT EDIT! #ifndef UNITREE_LEGGED_MSGS_MESSAGE_LOWSTATE_H #define UNITREE_LEGGED_MSGS_MESSAGE_LOWSTATE_H #include #include #include #include #include #include #include #include #include #include #include #include #include #include namespace unitree_legged_msgs { template struct LowState_ { typedef LowState_ Type; LowState_() : levelFlag(0) , commVersion(0) , robotID(0) , SN(0) , bandWidth(0) , imu() , motorState() , footForce() , footForceEst() , tick(0) , wirelessRemote() , reserve(0) , crc(0) , eeForceRaw() , eeForce() , position() , velocity() , velocity_w() { footForce.assign(0); footForceEst.assign(0); wirelessRemote.assign(0); } LowState_(const ContainerAllocator& _alloc) : levelFlag(0) , commVersion(0) , robotID(0) , SN(0) , bandWidth(0) , imu(_alloc) , motorState() , footForce() , footForceEst() , tick(0) , wirelessRemote() , reserve(0) , crc(0) , eeForceRaw() , eeForce() , position(_alloc) , velocity(_alloc) , velocity_w(_alloc) { (void)_alloc; motorState.assign( ::unitree_legged_msgs::MotorState_ (_alloc)); footForce.assign(0); footForceEst.assign(0); wirelessRemote.assign(0); eeForceRaw.assign( ::unitree_legged_msgs::Cartesian_ (_alloc)); eeForce.assign( ::unitree_legged_msgs::Cartesian_ (_alloc)); } typedef uint8_t _levelFlag_type; _levelFlag_type levelFlag; typedef uint16_t _commVersion_type; _commVersion_type commVersion; typedef uint16_t _robotID_type; _robotID_type robotID; typedef uint32_t _SN_type; _SN_type SN; typedef uint8_t _bandWidth_type; _bandWidth_type bandWidth; typedef ::unitree_legged_msgs::IMU_ _imu_type; _imu_type imu; typedef boost::array< ::unitree_legged_msgs::MotorState_ , 20> _motorState_type; _motorState_type motorState; typedef boost::array _footForce_type; _footForce_type footForce; typedef boost::array _footForceEst_type; _footForceEst_type footForceEst; typedef uint32_t _tick_type; _tick_type tick; typedef boost::array _wirelessRemote_type; _wirelessRemote_type wirelessRemote; typedef uint32_t _reserve_type; _reserve_type reserve; typedef uint32_t _crc_type; _crc_type crc; typedef boost::array< ::unitree_legged_msgs::Cartesian_ , 4> _eeForceRaw_type; _eeForceRaw_type eeForceRaw; typedef boost::array< ::unitree_legged_msgs::Cartesian_ , 4> _eeForce_type; _eeForce_type eeForce; typedef ::unitree_legged_msgs::Cartesian_ _position_type; _position_type position; typedef ::unitree_legged_msgs::Cartesian_ _velocity_type; _velocity_type velocity; typedef ::unitree_legged_msgs::Cartesian_ _velocity_w_type; _velocity_w_type velocity_w; typedef boost::shared_ptr< ::unitree_legged_msgs::LowState_ > Ptr; typedef boost::shared_ptr< ::unitree_legged_msgs::LowState_ const> ConstPtr; }; // struct LowState_ typedef ::unitree_legged_msgs::LowState_ > LowState; typedef boost::shared_ptr< ::unitree_legged_msgs::LowState > LowStatePtr; typedef boost::shared_ptr< ::unitree_legged_msgs::LowState const> LowStateConstPtr; // constants requiring out of line definition template std::ostream& operator<<(std::ostream& s, const ::unitree_legged_msgs::LowState_ & v) { ros::message_operations::Printer< ::unitree_legged_msgs::LowState_ >::stream(s, "", v); return s; } template bool operator==(const ::unitree_legged_msgs::LowState_ & lhs, const ::unitree_legged_msgs::LowState_ & rhs) { return lhs.levelFlag == rhs.levelFlag && lhs.commVersion == rhs.commVersion && lhs.robotID == rhs.robotID && lhs.SN == rhs.SN && lhs.bandWidth == rhs.bandWidth && lhs.imu == rhs.imu && lhs.motorState == rhs.motorState && lhs.footForce == rhs.footForce && lhs.footForceEst == rhs.footForceEst && lhs.tick == rhs.tick && lhs.wirelessRemote == rhs.wirelessRemote && lhs.reserve == rhs.reserve && lhs.crc == rhs.crc && lhs.eeForceRaw == rhs.eeForceRaw && lhs.eeForce == rhs.eeForce && lhs.position == rhs.position && lhs.velocity == rhs.velocity && lhs.velocity_w == rhs.velocity_w; } template bool operator!=(const ::unitree_legged_msgs::LowState_ & lhs, const ::unitree_legged_msgs::LowState_ & rhs) { return !(lhs == rhs); } } // namespace unitree_legged_msgs namespace ros { namespace message_traits { template struct IsFixedSize< ::unitree_legged_msgs::LowState_ > : TrueType { }; template struct IsFixedSize< ::unitree_legged_msgs::LowState_ const> : TrueType { }; template struct IsMessage< ::unitree_legged_msgs::LowState_ > : TrueType { }; template struct IsMessage< ::unitree_legged_msgs::LowState_ const> : TrueType { }; template struct HasHeader< ::unitree_legged_msgs::LowState_ > : FalseType { }; template struct HasHeader< ::unitree_legged_msgs::LowState_ const> : FalseType { }; template struct MD5Sum< ::unitree_legged_msgs::LowState_ > { static const char* value() { return "cef9d4f6b5a89bd6330896affb1bca88"; } static const char* value(const ::unitree_legged_msgs::LowState_&) { return value(); } static const uint64_t static_value1 = 0xcef9d4f6b5a89bd6ULL; static const uint64_t static_value2 = 0x330896affb1bca88ULL; }; template struct DataType< ::unitree_legged_msgs::LowState_ > { static const char* value() { return "unitree_legged_msgs/LowState"; } static const char* value(const ::unitree_legged_msgs::LowState_&) { return value(); } }; template struct Definition< ::unitree_legged_msgs::LowState_ > { static const char* value() { return "uint8 levelFlag\n" "uint16 commVersion # Old version Aliengo does not have\n" "uint16 robotID # Old version Aliengo does not have\n" "uint32 SN # Old version Aliengo does not have\n" "uint8 bandWidth # Old version Aliengo does not have\n" "IMU imu\n" "MotorState[20] motorState\n" "int16[4] footForce # force sensors # Old version Aliengo is different\n" "int16[4] footForceEst # force sensors # Old version Aliengo does not have\n" "uint32 tick # reference real-time from motion controller (unit: us)\n" "uint8[40] wirelessRemote # wireless commands\n" "uint32 reserve # Old version Aliengo does not have\n" "uint32 crc\n" "\n" "# Old version Aliengo does not have:\n" "Cartesian[4] eeForceRaw\n" "Cartesian[4] eeForce #it's a 1-DOF force infact, but we use 3-DOF here just for visualization \n" "Cartesian position # will delete\n" "Cartesian velocity # will delete\n" "Cartesian velocity_w # will delete\n" "\n" "================================================================================\n" "MSG: unitree_legged_msgs/IMU\n" "float32[4] quaternion\n" "float32[3] gyroscope\n" "float32[3] accelerometer\n" "int8 temperature\n" "================================================================================\n" "MSG: unitree_legged_msgs/MotorState\n" "uint8 mode # motor current mode \n" "float32 q # motor current position(rad)\n" "float32 dq # motor current speed(rad/s)\n" "float32 ddq # motor current speed(rad/s)\n" "float32 tauEst # current estimated output torque(N*m)\n" "float32 q_raw # motor current position(rad)\n" "float32 dq_raw # motor current speed(rad/s)\n" "float32 ddq_raw # motor current speed(rad/s)\n" "int8 temperature # motor temperature(slow conduction of temperature leads to lag)\n" "uint32[2] reserve\n" "================================================================================\n" "MSG: unitree_legged_msgs/Cartesian\n" "float32 x\n" "float32 y\n" "float32 z\n" ; } static const char* value(const ::unitree_legged_msgs::LowState_&) { return value(); } }; } // namespace message_traits } // namespace ros namespace ros { namespace serialization { template struct Serializer< ::unitree_legged_msgs::LowState_ > { template inline static void allInOne(Stream& stream, T m) { stream.next(m.levelFlag); stream.next(m.commVersion); stream.next(m.robotID); stream.next(m.SN); stream.next(m.bandWidth); stream.next(m.imu); stream.next(m.motorState); stream.next(m.footForce); stream.next(m.footForceEst); stream.next(m.tick); stream.next(m.wirelessRemote); stream.next(m.reserve); stream.next(m.crc); stream.next(m.eeForceRaw); stream.next(m.eeForce); stream.next(m.position); stream.next(m.velocity); stream.next(m.velocity_w); } ROS_DECLARE_ALLINONE_SERIALIZER }; // struct LowState_ } // namespace serialization } // namespace ros namespace ros { namespace message_operations { template struct Printer< ::unitree_legged_msgs::LowState_ > { template static void stream(Stream& s, const std::string& indent, const ::unitree_legged_msgs::LowState_& v) { s << indent << "levelFlag: "; Printer::stream(s, indent + " ", v.levelFlag); s << indent << "commVersion: "; Printer::stream(s, indent + " ", v.commVersion); s << indent << "robotID: "; Printer::stream(s, indent + " ", v.robotID); s << indent << "SN: "; Printer::stream(s, indent + " ", v.SN); s << indent << "bandWidth: "; Printer::stream(s, indent + " ", v.bandWidth); s << indent << "imu: "; s << std::endl; Printer< ::unitree_legged_msgs::IMU_ >::stream(s, indent + " ", v.imu); s << indent << "motorState[]" << std::endl; for (size_t i = 0; i < v.motorState.size(); ++i) { s << indent << " motorState[" << i << "]: "; s << std::endl; s << indent; Printer< ::unitree_legged_msgs::MotorState_ >::stream(s, indent + " ", v.motorState[i]); } s << indent << "footForce[]" << std::endl; for (size_t i = 0; i < v.footForce.size(); ++i) { s << indent << " footForce[" << i << "]: "; Printer::stream(s, indent + " ", v.footForce[i]); } s << indent << "footForceEst[]" << std::endl; for (size_t i = 0; i < v.footForceEst.size(); ++i) { s << indent << " footForceEst[" << i << "]: "; Printer::stream(s, indent + " ", v.footForceEst[i]); } s << indent << "tick: "; Printer::stream(s, indent + " ", v.tick); s << indent << "wirelessRemote[]" << std::endl; for (size_t i = 0; i < v.wirelessRemote.size(); ++i) { s << indent << " wirelessRemote[" << i << "]: "; Printer::stream(s, indent + " ", v.wirelessRemote[i]); } s << indent << "reserve: "; Printer::stream(s, indent + " ", v.reserve); s << indent << "crc: "; Printer::stream(s, indent + " ", v.crc); s << indent << "eeForceRaw[]" << std::endl; for (size_t i = 0; i < v.eeForceRaw.size(); ++i) { s << indent << " eeForceRaw[" << i << "]: "; s << std::endl; s << indent; Printer< ::unitree_legged_msgs::Cartesian_ >::stream(s, indent + " ", v.eeForceRaw[i]); } s << indent << "eeForce[]" << std::endl; for (size_t i = 0; i < v.eeForce.size(); ++i) { s << indent << " eeForce[" << i << "]: "; s << std::endl; s << indent; Printer< ::unitree_legged_msgs::Cartesian_ >::stream(s, indent + " ", v.eeForce[i]); } s << indent << "position: "; s << std::endl; Printer< ::unitree_legged_msgs::Cartesian_ >::stream(s, indent + " ", v.position); s << indent << "velocity: "; s << std::endl; Printer< ::unitree_legged_msgs::Cartesian_ >::stream(s, indent + " ", v.velocity); s << indent << "velocity_w: "; s << std::endl; Printer< ::unitree_legged_msgs::Cartesian_ >::stream(s, indent + " ", v.velocity_w); } }; } // namespace message_operations } // namespace ros #endif // UNITREE_LEGGED_MSGS_MESSAGE_LOWSTATE_H