Skip to content

Commit

Permalink
Merge pull request #4 from MiRoboticsLab/v1.3.0.0
Browse files Browse the repository at this point in the history
V1.3.0.0
  • Loading branch information
ruheng authored Jan 17, 2024
2 parents 9332bf5 + 015d963 commit 1a0ac94
Show file tree
Hide file tree
Showing 25 changed files with 1,701 additions and 42 deletions.
1 change: 0 additions & 1 deletion connector/config/wifi.toml
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
[wifi]
user_boots_first_time = false
[wifi.ssid]
password = "password"
provider = "provider"
4 changes: 4 additions & 0 deletions connector/config/wifirecord.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[wifi]
[wifi.ssid]
type = "type"
provider = "ip"
43 changes: 38 additions & 5 deletions connector/include/connector/connector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,11 @@
#include <std_msgs/msg/string.hpp>
#include <std_msgs/msg/bool.hpp>

#include <protocol/msg/wifi_info.hpp>
#include <protocol/msg/notify_to_app.hpp>
#include <protocol/msg/bluetooth_status.hpp>
#include <protocol/msg/bledfu_progress.hpp>

#include <protocol/msg/audio_play.hpp>
#include <protocol/msg/connector_status.hpp>
#include <protocol/msg/touch_status.hpp>
Expand All @@ -68,7 +73,7 @@ namespace cyberdog
namespace interaction
{
namespace py = pybind11;
static const unsigned int LINE_MAX_SIZE {16384}; /*!< 行最大值:2kb */
static const unsigned int LINE_MAX_SIZE {16384}; /*!< 行最大值:2kb */

/*! \file connector.hpp
\brief 连接模块。
Expand All @@ -94,7 +99,13 @@ class Connector final : public rclcpp::Node
using LedSrv = protocol::srv::LedExecute; /*!< [service 类型]LED 驱动服务 */
using CameraSrv = protocol::srv::CameraService; /*!< [service 类型]相机 驱动服务 */

using TimeType = std::chrono::time_point<std::chrono::system_clock>; /*!< 超时 */
using NotifyToAppMsg = protocol::msg::NotifyToApp; /*!< [topic 类型]通知APP连接状态消息 */
using WIFIINFOMSG = protocol::msg::WifiInfo;
using BLUETOOTHSTATUSMSG = protocol::msg::BluetoothStatus;
using ConnectorStatus = std_msgs::msg::String;
using BLEDfuProgressMsg = protocol::msg::BLEDFUProgress;

using TimeType = std::chrono::time_point<std::chrono::system_clock>; /*!< 超时 */
enum ShellEnum
{
shell = 1993, /*!< 异常结束, 执行shell命令错误 */
Expand All @@ -110,16 +121,16 @@ class Connector final : public rclcpp::Node
const std::function<uint(uint16_t)>,
const std::function<uint(uint8_t)>,
const std::function<uint(uint16_t)>,
const std::function<uint(
const std::string,
const std::string)>); /*!< 初始化 */
const std::function<uint(const std::string, const std::string)>,
const std::function<bool(bool)>); /*!< 初始化 */

public:
std::function<uint(uint16_t)> CtrlAudio; /*!< [客户端]控制语音 */
std::function<uint(uint8_t)> CtrlCamera; /*!< [客户端]控制相机 */
std::function<uint(uint16_t)> CtrlLed; /*!< [客户端]控制led */
std::function<uint(const std::string, const std::string)>
CtrlWifi; /*!< [客户端]控制wifi */
std::function<bool(bool)> CtrlAdvertising; /*!< [客户端]控制蓝牙 */

private:
bool InitPythonInterpreter(); /*!< 初始化 python 解释器 */
Expand Down Expand Up @@ -183,6 +194,28 @@ class Connector final : public rclcpp::Node
rclcpp::CallbackGroup::SharedPtr touch_cb_group_ {nullptr}; /*!< [回调组] touch */
rclcpp::CallbackGroup::SharedPtr img_cb_group_ {nullptr}; /*!< [回调组] img */
rclcpp::CallbackGroup::SharedPtr pub_cb_group_ {nullptr}; /*!< [回调组] pub */

void APPSendWiFiCallback(const protocol::msg::WifiInfo::SharedPtr msg);
void AppConnectState(const std_msgs::msg::Bool msg);
void BtStatusCallback(const protocol::msg::BluetoothStatus::SharedPtr msg);
void BledfuProgressCallback(const BLEDfuProgressMsg::SharedPtr msg);
bool WriteToFile(
const std::string ssid,
const std::string ip,
const std::string type);

NotifyToAppMsg notify_to_app_msg_;
ConnectorStatus connector_status_msg_;
rclcpp::Subscription<WIFIINFOMSG>::SharedPtr wifi_info_sub_ {nullptr};
rclcpp::Publisher<NotifyToAppMsg>::SharedPtr notify_to_app_pub_ {nullptr};
rclcpp::Subscription<BLUETOOTHSTATUSMSG>::SharedPtr bluetooth_status_sub_ {nullptr};
rclcpp::Subscription<BLEDfuProgressMsg>::SharedPtr bledfu_progress_sub_ {nullptr};
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr connector_init_pub_ {nullptr};
std::string wifi_record_dir_ {""}; /*!< wifi 类型记录文件路径 */
bool connect_network_status = true;
int connect_code = -1;
bool bledfu_progress_status = true;
bool camera_callback_flag = false;
}; // class Connector
} // namespace interaction
} // namespace cyberdog
Expand Down
69 changes: 69 additions & 0 deletions connector/include/connector/ctrl_bluetooth.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
// Copyright (c) 2023 Beijing Xiaomi Mobile Software Co., Ltd. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef CONNECTOR__CTRL_BLUETOOTH_HPP_
#define CONNECTOR__CTRL_BLUETOOTH_HPP_

#include <unistd.h>
#include <string>
#include <iostream>
#include <sstream>
#include <regex>
#include <vector>
#include <cstdlib>
#include <cstdio>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/wait_set.hpp"
#include "cyberdog_common/cyberdog_log.hpp"
#include "cyberdog_common/cyberdog_toml.hpp"
#include "protocol/msg/audio_play.hpp"
#include "protocol/msg/bluetooth_status.hpp"
#include "protocol/srv/bms_cmd.hpp"
#include "std_srvs/srv/trigger.hpp"

namespace cyberdog
{
namespace interaction
{
class CtrlBluetooth final : public rclcpp::Node
{
public:
explicit CtrlBluetooth(const std::string name);
~CtrlBluetooth();
bool CtrlAdvertising(bool enable);

bool WriteToFile(
const std::string ssid,
const std::string ip,
const std::string type);
bool IsConnectApp();

private:
bool Init();
std::string runCommand(const std::string & cmd);
std::vector<std::string> parseConnectionsOutput(const std::string & output);
void BluetoothStatusCallback(
const protocol::msg::BluetoothStatus::SharedPtr msg);
bool DisconnectBluetooth();

private:
int bluetooth_connect_status_ = -1;
int bluetooth_advertising_status_ = -1;

rclcpp::Subscription<protocol::msg::BluetoothStatus>::SharedPtr bluetooth_status_sub_ {nullptr};
rclcpp::Client<protocol::srv::BmsCmd>::SharedPtr control_advertise_client_ {nullptr};
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr disconnect_app_bt_srv_ {nullptr};
}; // class CtrlBluetooth
} // namespace interaction
} // namespace cyberdog
#endif // CONNECTOR__CTRL_BLUETOOTH_HPP_
Loading

0 comments on commit 1a0ac94

Please sign in to comment.