Merge pull request #4478 from cyberbotics/for4475

fix4475
This commit is contained in:
zimmy87 2022-05-02 12:19:08 +00:00 коммит произвёл GitHub
Родитель 284f4654f0 5a39bb97e8
Коммит 9b68c3dc34
Не найден ключ, соответствующий данной подписи
Идентификатор ключа GPG: 4AEE18F83AFDEB23
1 изменённых файлов: 5 добавлений и 5 удалений

Просмотреть файл

@ -1202,15 +1202,15 @@ void AirsimROSWrapper::append_static_camera_tf(VehicleROS* vehicle_ros, const st
{
geometry_msgs::msg::TransformStamped static_cam_tf_body_msg;
static_cam_tf_body_msg.header.frame_id = vehicle_ros->vehicle_name_ + "/" + odom_frame_id_;
static_cam_tf_body_msg.child_frame_id = camera_name + "_body/static";
static_cam_tf_body_msg.child_frame_id = vehicle_ros->vehicle_name_ + "/" + camera_name + "_body/static";
static_cam_tf_body_msg.transform = get_transform_msg_from_airsim(camera_setting.position, camera_setting.rotation);
if (isENU_) {
convert_tf_msg_to_enu(static_cam_tf_body_msg);
}
geometry_msgs::msg::TransformStamped static_cam_tf_optical_msg;
static_cam_tf_optical_msg.header.frame_id = static_cam_tf_body_msg.header.frame_id;
geometry_msgs::msg::TransformStamped static_cam_tf_optical_msg = static_cam_tf_body_msg;
static_cam_tf_optical_msg.child_frame_id = vehicle_ros->vehicle_name_ + "/" + camera_name + "_optical/static";
static_cam_tf_optical_msg.child_frame_id = camera_name + "_optical/static";
static_cam_tf_optical_msg.transform = get_camera_optical_tf_from_body_tf(static_cam_tf_body_msg.transform);
@ -1356,7 +1356,7 @@ void AirsimROSWrapper::publish_camera_tf(const ImageResponse& img_response, cons
geometry_msgs::msg::TransformStamped cam_tf_body_msg;
cam_tf_body_msg.header.stamp = rclcpp::Time(img_response.time_stamp);
cam_tf_body_msg.header.frame_id = frame_id;
cam_tf_body_msg.child_frame_id = child_frame_id + "_body";
cam_tf_body_msg.child_frame_id = frame_id + "/" + child_frame_id + "_body";
cam_tf_body_msg.transform = get_transform_msg_from_airsim(img_response.camera_position, img_response.camera_orientation);
if (isENU_) {
@ -1366,7 +1366,7 @@ void AirsimROSWrapper::publish_camera_tf(const ImageResponse& img_response, cons
geometry_msgs::msg::TransformStamped cam_tf_optical_msg;
cam_tf_optical_msg.header.stamp = rclcpp::Time(img_response.time_stamp);
cam_tf_optical_msg.header.frame_id = frame_id;
cam_tf_optical_msg.child_frame_id = child_frame_id + "_optical";
cam_tf_optical_msg.child_frame_id = frame_id + "/" + child_frame_id + "_optical";
cam_tf_optical_msg.transform = get_camera_optical_tf_from_body_tf(cam_tf_body_msg.transform);
tf_broadcaster_->sendTransform(cam_tf_body_msg);