Робот-собака МОРС
  • Общая информация
  • Технические характеристики
  • Комплект поставки
  • Безопасность
  • Быстрый старт
  • Полезные ссылки
  • Обозначения
  • Настройка и обслуживание
    • Джойстик RadioLink T8S
    • Зарядка батареи
    • Выключение робота
    • Подключение к роботу по сети
      • Параметры точки доступа
      • Подключение через SSH
      • Подключение через Remote Desktop Protocol (RDP)
      • Подключение через SFTP
      • Настройка VSCode
    • Подключение робота к Интернету
    • Подключение к ROS на роботе
    • Установка ПО
    • Графический интерфейс
    • Ubuntu-сервис
    • Смена пароля пользователя
    • Обновление дампа памяти BLDC драйвера 10А
    • Замена приводного ремня
    • Переинициализация приводов
    • Подключение дополнительных устройств
      • Подключение головы VBRoboHead
      • Подключение видеокамеры Intel Realsense D435i
      • Подключение видеокамеры Luxonis OAK-D Lite
      • Подключение лидара RPLIDAR A1M8-R5
    • Обновление управляющего ПО
    • Возврат к заводским настройкам
    • Устранение неполадок
  • Симуляция
    • Описание имитационной модели
    • Параметры файла bringup_sim.launch
    • Подключение джойстиков к ПК
    • ROS-параметры
    • OpenAI Gymnasium
  • Устройство робота
    • Электроника
    • Программное обеспечение
    • Файлы и папки в системе
    • Советы по разработке собственного ПО
    • Примеры
    • ROS-пакеты
      • mors_hardware
        • bhi360_imu_node
        • ds4_teleop
        • power_bridge
        • radiolink_teleop
        • status_tracker
      • mors_base
        • champ_msgs
        • cmd_commutator
        • joy_converter
        • locomotion_controller
        • log_writer
        • mors
        • servo_state_lcm2ros
        • servo_cmd_ros2lcm
      • mors_pc
        • robogui
        • mors_sim
    • ROS-топики
    • ROS-сервисы
      • robot_mode
      • robot_action
      • stride_height
      • joints_kp
      • joints_kd
    • LCM-каналы
Powered by GitBook
On this page
  • ROS API
  • Параметры
  • Входящие топики
  • Исходящие топики
  1. Устройство робота
  2. ROS-пакеты
  3. mors_base

cmd_commutator

Данный модуль подписывается на топики всех включенных в данный момент задающих устройств (ПК, джойстики и т.д.), и выводит сообщения самого приоритетного из них. Поддерживает до четырех разных устройств.

ROS API

ROS API состоит из config-файла, вызова сервисов, входящих и исходящих топиков.

Параметры

Файл параметров располагается в папке config

  • frequency (по умолчанию: 40) - частота, на которой работает модуль

  • input1_cmd_vel_topic (по умолчанию: "ds4/cmd_vel") - название входящего топика желаемой скорости робота для устройства №1

  • input1_cmd_pose_topic (по умолчанию: "ds4/cmd_pose") - название входящего топика желаемого положения и ориентации корпуса для устройства №1

  • input1_cmd_ef_pose_topic (по умолчанию: "ds4/ef_position/command") - название входящего топика желаемого положения ступни робота для устройства №1

  • input1_cmd_joint_pos_topic (по умолчанию: "ds4/joint_group_position_controller/command") - название входящего топика желаемого положения сочленений робота для устройства №1

  • input1_status_topic (по умолчанию: "ds4/cur_device") - название входящего топика статуса подключения устройства №1

  • input2_cmd_vel_topic (по умолчанию: "radiolink/cmd_vel") - название входящего топика желаемой скорости робота для устройства №2

  • input2_cmd_pose_topic (по умолчанию: "radiolink/cmd_pose") - название входящего топика желаемого положения и ориентации корпуса для устройства №2

  • input2_cmd_ef_pose_topic (по умолчанию: "radiolink/ef_position/command") - название входящего топика желаемого положения ступни робота для устройства №2

  • input2_cmd_joint_pos_topic (по умолчанию: "radiolink/joint_group_position_controller/command") - название входящего топика желаемого положения сочленений робота для устройства №2

  • input2_status_topic (по умолчанию: "radiolink/status") - название входящего топика статуса подключения устройства №2

  • input3_cmd_vel_topic (по умолчанию: "nav/cmd_vel") - название входящего топика желаемой скорости робота для устройства №3

  • input3_cmd_pose_topic (по умолчанию: "nav/cmd_pose") - название входящего топика желаемого положения и ориентации корпуса для устройства №3

  • input3_cmd_ef_pose_topic (по умолчанию: "nav/ef_position/command") - название входящего топика желаемого положения ступни робота для устройства №3

  • input3_cmd_joint_pos_topic (по умолчанию: "nav/joint_group_position_controller/command") -

  • input3_status_topic (по умолчанию: "nav/status") - название входящего топика желаемого положения сочленений робота для устройства №3

  • input4_cmd_vel_topic (по умолчанию: "gui/cmd_vel") - название входящего топика желаемой скорости робота для устройства №4

  • input4_cmd_pose_topic (по умолчанию: "gui/cmd_pose") - название входящего топика желаемого положения и ориентации корпуса для устройства №4

  • input4_cmd_ef_pose_topic (по умолчанию: "gui/ef_position/command") - название входящего топика желаемого положения ступни робота для устройства №4

  • input4_cmd_joint_pos_topic (по умолчанию: "gui/joint_group_position_controller/command") -

  • input4_status_topic (по умолчанию: "gui/status") - название входящего топика желаемого положения сочленений робота для устройства №4

  • output_cmd_vel_topic (по умолчанию: "cmd_vel") - название исходящего топика желаемой скорости робота

  • output_cmd_pose_topic (по умолчанию: "cmd_pose") - название исходящего топика желаемого положения и ориентации корпуса

  • output_cmd_ef_pose_topic (по умолчанию: "ef_position/command") - название исходящего топика желаемого положения ступни робота

  • output_cmd_joint_pos_topic (по умолчанию: "joint_group_position_controller/command") - название исходящего топика желаемого положения сочленений робота

  • output_status_topic (по умолчанию: "cur_device") - название исходящего топика, отображающего номер подключенного сейчас наиболее приоритетного устройства

Входящие топики

Здесь описываются названия топиков, которые установлены в пакете по умолчанию.

У входящих топиков, в зависимости от устройства, стоят разные приставки. При необходимости подключения иного устройства, вы можете переименовать приставки нужных вам топиков в config-файле на те, который нужны именно вам. Список приставок по умолчанию:

  • head - передача данных с джойстика Sony Dualshock 4

  • radiolink - передача данныз с джойстика Radiolink T8S

  • nav - передача данных с модуля навигации

  • gui - передача данный из ПО Robogui

Приоритет устройств идет в порядке возрастания по списку списку. Т.е., если у вас одновременно включены джойстик Radiolink T8S и ПО Robogui, то cmd_commutator на выходе будет давать данные из джойстика, так как у него больший приоритет.

Исходящие топики

Previouschamp_msgsNextjoy_converter

Last updated 8 months ago

В остальной части, топики дублируют свои имена и функции с исходящими, кроме топика status () . Он необходим для отображения информации о подключении устройства: True - устройство подключено, False - устройство не подключено.

cmd_vel () - желаемая скорость перемещения робота

cmd_pose () - желаемые положения и ориентация корпуса робота

ef_position/command () - желаемые положения ступней ног робота

joint_group_position_controller/command () - желаемое угловое положение сочленений робота

cur_device () - текущее подключенное устройство. 1 - Dualshock 4, 2 - Radiolink T8S, 3 - модуль навигации, 4 - Robogui, 0 - ни одного устройства.

std_msgs/Bool
geometry_msgs/Twist
geometry_msgs/Twist
geometry_msgs/PoseArray
trajectory_msgs/JointTrajectoryPoint
std_msgs/UInt8