Skip to content

Commit

Permalink
bug fixed
Browse files Browse the repository at this point in the history
  • Loading branch information
tmori committed Nov 14, 2024
1 parent 27ce362 commit 6070df5
Show file tree
Hide file tree
Showing 3 changed files with 132 additions and 28 deletions.
4 changes: 2 additions & 2 deletions drone_api/libs/pdu_info.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
HAKO_AVATOR_CHANNEL_ID_CMD_MOVE = 6
HAKO_AVATOR_CHANNEL_ID_CMD_LAND = 7
HAKO_AVATOR_CHANNEL_ID_GAME_CTRL = 8
HAKO_AVATOR_CHANNEL_ID_CMD_CAMERA = 9
HAKO_AVATOR_CHANNEL_ID_BATTERY_STAT= 10
HAKO_AVATOR_CHANNEL_ID_BATTERY_STAT= 0
HAKO_AVATOR_CHANNEL_ID_CMD_CAMERA = 10
HAKO_AVATOR_CHANNEL_ID_CAMERA_DATA = 11
HAKO_AVATOR_CHANNEL_ID_CMD_CAMERA_MOVE = 12
HAKO_AVATOR_CHANNEL_ID_CAMERA_INFO = 13
Expand Down
2 changes: 1 addition & 1 deletion drone_api/sample/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ def main():
print(f"Usage: {sys.argv[0]} <config_path>")
return 1

client = hakosim.MultirotorClient(sys.argv[1])
client = hakosim.MultirotorClient(sys.argv[1], "DroneTransporter")
client.confirmConnection()
client.enableApiControl(True)
client.armDisarm(True)
Expand Down
154 changes: 129 additions & 25 deletions drone_api/sample/custom.json
Original file line number Diff line number Diff line change
@@ -1,5 +1,43 @@
{
"robots": [
{
"name": "Baggage1",
"rpc_pdu_readers": [],
"rpc_pdu_writers": [],
"shm_pdu_readers": [],
"shm_pdu_writers": [
{
"type": "geometry_msgs/Twist",
"org_name": "pos",
"name": "Baggage1_pos",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 0,
"pdu_size": 112,
"write_cycle": 1,
"method_type": "SHM"
}
]
},
{
"name": "Baggage2",
"rpc_pdu_readers": [],
"rpc_pdu_writers": [],
"shm_pdu_readers": [],
"shm_pdu_writers": [
{
"type": "geometry_msgs/Twist",
"org_name": "pos",
"name": "Baggage2_pos",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 0,
"pdu_size": 112,
"write_cycle": 1,
"method_type": "SHM"
}
]
},
{
"name": "DroneTransporter",
"rpc_pdu_readers": [],
Expand All @@ -12,7 +50,7 @@
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduReader",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduReaderConverter",
"channel_id": 0,
"pdu_size": 88,
"pdu_size": 112,
"write_cycle": 1,
"method_type": "SHM"
},
Expand All @@ -23,7 +61,7 @@
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduReader",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduReaderConverter",
"channel_id": 1,
"pdu_size": 48,
"pdu_size": 72,
"write_cycle": 1,
"method_type": "SHM"
},
Expand All @@ -34,7 +72,18 @@
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 3,
"pdu_size": 56,
"pdu_size": 80,
"write_cycle": 1,
"method_type": "SHM"
},
{
"type": "hako_msgs/Disturbance",
"org_name": "drone_disturbance",
"name": "DroneTransporter_drone_disturbance",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduReader",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduReaderConverter",
"channel_id": 4,
"pdu_size": 88,
"write_cycle": 1,
"method_type": "SHM"
},
Expand All @@ -45,7 +94,7 @@
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 5,
"pdu_size": 32,
"pdu_size": 64,
"write_cycle": 1,
"method_type": "SHM"
},
Expand All @@ -56,7 +105,7 @@
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 6,
"pdu_size": 48,
"pdu_size": 80,
"write_cycle": 1,
"method_type": "SHM"
},
Expand All @@ -67,18 +116,29 @@
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 7,
"pdu_size": 32,
"pdu_size": 64,
"write_cycle": 1,
"method_type": "SHM"
},
{
"type": "hako_msgs/HakoCmdMagnetHolder",
"org_name": "hako_cmd_magnet_holder",
"name": "DroneTransporter_hako_cmd_magnet_holder",
"type": "hako_msgs/GameControllerOperation",
"org_name": "hako_cmd_game",
"name": "DroneTransporter_hako_cmd_game",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 8,
"pdu_size": 16,
"pdu_size": 136,
"write_cycle": 1,
"method_type": "SHM"
},
{
"type": "hako_msgs/HakoBatteryStatus",
"org_name": "hako_battery",
"name": "DroneTransporter_hako_battery",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduReader",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduReaderConverter",
"channel_id": 9,
"pdu_size": 56,
"write_cycle": 1,
"method_type": "SHM"
},
Expand All @@ -89,7 +149,29 @@
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 10,
"pdu_size": 20,
"pdu_size": 44,
"write_cycle": 1,
"method_type": "SHM"
},
{
"type": "hako_msgs/HakoCmdCameraMove",
"org_name": "hako_cmd_camera_move",
"name": "DroneTransporter_hako_cmd_camera_move",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 12,
"pdu_size": 64,
"write_cycle": 1,
"method_type": "SHM"
},
{
"type": "hako_msgs/HakoCmdMagnetHolder",
"org_name": "hako_cmd_magnet_holder",
"name": "DroneTransporter_hako_cmd_magnet_holder",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 14,
"pdu_size": 40,
"write_cycle": 1,
"method_type": "SHM"
}
Expand All @@ -102,18 +184,29 @@
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 2,
"pdu_size": 280,
"pdu_size": 304,
"write_cycle": 1,
"method_type": "SHM"
},
{
"type": "hako_msgs/Disturbance",
"org_name": "drone_disturbance",
"name": "DroneTransporter_drone_disturbance",
"type": "hako_msgs/HakoCameraData",
"org_name": "hako_camera_data",
"name": "DroneTransporter_hako_camera_data",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 4,
"pdu_size": 8,
"channel_id": 11,
"pdu_size": 102968,
"write_cycle": 1,
"method_type": "SHM"
},
{
"type": "hako_msgs/HakoCameraInfo",
"org_name": "hako_cmd_camera_info",
"name": "DroneTransporter_hako_cmd_camera_info",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 13,
"pdu_size": 56,
"write_cycle": 1,
"method_type": "SHM"
},
Expand All @@ -123,20 +216,31 @@
"name": "DroneTransporter_hako_status_magnet_holder",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 9,
"pdu_size": 8,
"channel_id": 15,
"pdu_size": 32,
"write_cycle": 1,
"method_type": "SHM"
},
{
"type": "hako_msgs/HakoCameraData",
"org_name": "hako_camera_data",
"name": "DroneTransporter_hako_camera_data",
"type": "sensor_msgs/PointCloud2",
"org_name": "lidar_points",
"name": "DroneTransporter_lidar_points",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 11,
"pdu_size": 102668,
"write_cycle": 1,
"channel_id": 16,
"pdu_size": 177400,
"write_cycle": 5,
"method_type": "SHM"
},
{
"type": "geometry_msgs/Twist",
"org_name": "lidar_pos",
"name": "DroneTransporter_lidar_pos",
"class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriter",
"conv_class_name": "Hakoniwa.PluggableAsset.Communication.Pdu.Raw.RawPduWriterConverter",
"channel_id": 17,
"pdu_size": 72,
"write_cycle": 5,
"method_type": "SHM"
}
]
Expand Down

0 comments on commit 6070df5

Please sign in to comment.