4242#include < std_msgs/msg/string.hpp>
4343#include < std_msgs/msg/bool.hpp>
4444
45+ #include < protocol/msg/wifi_info.hpp>
46+ #include < protocol/msg/notify_to_app.hpp>
47+ #include < protocol/msg/bluetooth_status.hpp>
48+ #include < protocol/msg/bledfu_progress.hpp>
49+
4550#include < protocol/msg/audio_play.hpp>
4651#include < protocol/msg/connector_status.hpp>
4752#include < protocol/msg/touch_status.hpp>
@@ -68,7 +73,7 @@ namespace cyberdog
6873namespace interaction
6974{
7075namespace py = pybind11;
71- static const unsigned int LINE_MAX_SIZE {16384 }; /* !< 行最大值:2kb */
76+ static const unsigned int LINE_MAX_SIZE {16384 }; /* !< 行最大值:2kb */
7277
7378/* ! \file connector.hpp
7479 \brief 连接模块。
@@ -94,7 +99,13 @@ class Connector final : public rclcpp::Node
9499 using LedSrv = protocol::srv::LedExecute; /* !< [service 类型]LED 驱动服务 */
95100 using CameraSrv = protocol::srv::CameraService; /* !< [service 类型]相机 驱动服务 */
96101
97- using TimeType = std::chrono::time_point<std::chrono::system_clock>; /* !< 超时 */
102+ using NotifyToAppMsg = protocol::msg::NotifyToApp; /* !< [topic 类型]通知APP连接状态消息 */
103+ using WIFIINFOMSG = protocol::msg::WifiInfo;
104+ using BLUETOOTHSTATUSMSG = protocol::msg::BluetoothStatus;
105+ using ConnectorStatus = std_msgs::msg::String;
106+ using BLEDfuProgressMsg = protocol::msg::BLEDFUProgress;
107+
108+ using TimeType = std::chrono::time_point<std::chrono::system_clock>; /* !< 超时 */
98109 enum ShellEnum
99110 {
100111 shell = 1993 , /* !< 异常结束, 执行shell命令错误 */
@@ -110,16 +121,16 @@ class Connector final : public rclcpp::Node
110121 const std::function<uint(uint16_t )>,
111122 const std::function<uint(uint8_t )>,
112123 const std::function<uint(uint16_t )>,
113- const std::function<uint(
114- const std::string,
115- const std::string)>); /* !< 初始化 */
124+ const std::function<uint(const std::string, const std::string)>,
125+ const std::function<bool(bool )>); /* !< 初始化 */
116126
117127public:
118128 std::function<uint(uint16_t )> CtrlAudio; /* !< [客户端]控制语音 */
119129 std::function<uint(uint8_t )> CtrlCamera; /* !< [客户端]控制相机 */
120130 std::function<uint(uint16_t )> CtrlLed; /* !< [客户端]控制led */
121131 std::function<uint(const std::string, const std::string)>
122132 CtrlWifi; /* !< [客户端]控制wifi */
133+ std::function<bool (bool )> CtrlAdvertising; /* !< [客户端]控制蓝牙 */
123134
124135private:
125136 bool InitPythonInterpreter (); /* !< 初始化 python 解释器 */
@@ -183,6 +194,28 @@ class Connector final : public rclcpp::Node
183194 rclcpp::CallbackGroup::SharedPtr touch_cb_group_ {nullptr }; /* !< [回调组] touch */
184195 rclcpp::CallbackGroup::SharedPtr img_cb_group_ {nullptr }; /* !< [回调组] img */
185196 rclcpp::CallbackGroup::SharedPtr pub_cb_group_ {nullptr }; /* !< [回调组] pub */
197+
198+ void APPSendWiFiCallback (const protocol::msg::WifiInfo::SharedPtr msg);
199+ void AppConnectState (const std_msgs::msg::Bool msg);
200+ void BtStatusCallback (const protocol::msg::BluetoothStatus::SharedPtr msg);
201+ void BledfuProgressCallback (const BLEDfuProgressMsg::SharedPtr msg);
202+ bool WriteToFile (
203+ const std::string ssid,
204+ const std::string ip,
205+ const std::string type);
206+
207+ NotifyToAppMsg notify_to_app_msg_;
208+ ConnectorStatus connector_status_msg_;
209+ rclcpp::Subscription<WIFIINFOMSG>::SharedPtr wifi_info_sub_ {nullptr };
210+ rclcpp::Publisher<NotifyToAppMsg>::SharedPtr notify_to_app_pub_ {nullptr };
211+ rclcpp::Subscription<BLUETOOTHSTATUSMSG>::SharedPtr bluetooth_status_sub_ {nullptr };
212+ rclcpp::Subscription<BLEDfuProgressMsg>::SharedPtr bledfu_progress_sub_ {nullptr };
213+ rclcpp::Publisher<std_msgs::msg::String>::SharedPtr connector_init_pub_ {nullptr };
214+ std::string wifi_record_dir_ {" " }; /* !< wifi 类型记录文件路径 */
215+ bool connect_network_status = true ;
216+ int connect_code = -1 ;
217+ bool bledfu_progress_status = true ;
218+ bool camera_callback_flag = false ;
186219}; // class Connector
187220} // namespace interaction
188221} // namespace cyberdog
0 commit comments