ros2/ros1_bridge

ros1_bridge does not bridge service if service field name changes, even if mapped in mapping_rules.yaml

RaAndOn opened this issue · 17 comments

Bug report

I have found that if a service field name changes between ROS1 and ROS2, even if the change is mapped in a mapping_rules.yaml, does not bridge the service.

Required Info:

  • Operating System:
    • Ubuntu 20.04.
  • Installation type:
    • Source
  • Version or commit hash:
    • Tag 0.9.4
  • DDS implementation:
    • Default (Fast RTPS)
  • Client library (if applicable):
    • N/A

Steps to reproduce issue

I created a stripped down project to demonstrate the issue:

.
├── ros1_ws
│   └── src
│       └── example_interfaces
│           ├── CMakeLists.txt
│           ├── package.xml
│           └── srv
│               ├── CustomServiceFails.srv
│               └── CustomServiceSucceeds1.srv
└── ros2_ws
    └── src
        └── example_interfaces
            ├── CMakeLists.txt
            ├── mapping_rules.yaml
            ├── package.xml
            └── srv
                ├── CustomServiceFails.srv
                └── CustomServiceSucceeds2.srv

ROS1 CMakeLists.txt

cmake_minimum_required(VERSION 2.8.3)

project(example_interfaces)

set(MSG_DEPS std_msgs)

set(BUILD_DEPS ${MSG_DEPS} message_generation)

set(RUNTIME_DEPS ${MSG_DEPS} message_runtime)

find_package(catkin REQUIRED COMPONENTS ${BUILD_DEPS})

add_service_files(DIRECTORY srv FILES
    CustomServiceFails.srv
    CustomServiceSucceeds1.srv
)

generate_messages(DEPENDENCIES ${MSG_DEPS})

catkin_package(CATKIN_DEPENDS ${RUNTIME_DEPS})

ROS1 package.xml

<?xml version="1.0" ?>
<package format="2">
  <name>example_interfaces</name>
  <version>0.0.1</version>
  <description>
    This pacakge contains a single service to demonstrate a bug in the ros1_bridge
  </description>
  <maintainer email="joshua.raanan@gmail.com">Joshua Ra'anan</maintainer>

  <license>BSD</license>
  <buildtool_depend>catkin</buildtool_depend>

  <depend>std_msgs</depend>

  <build_depend>message_generation</build_depend>
  <exec_depend>message_runtime</exec_depend>

  <export>
  </export>
</package>

ROS1 CustomServiceFails.srv

float64 same_field_name
---
float64 differentFieldName

ROS1 CustomServiceSucceeds1.srv

float64 fine_name
---
float64 also_fine_name

ROS2 CMakeLists.txt

cmake_minimum_required(VERSION 3.5)
project(example_interfaces)

if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

set(MSG_DEPS
  std_msgs
)

set(BUILD_DEPS
  ament_cmake
  rosidl_default_generators
  ${MSG_DEPS}
)

foreach(DEP ${BUILD_DEPS})
  find_package(${DEP} REQUIRED)
endforeach()

find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
    srv/CustomServiceFails.srv
    srv/CustomServiceSucceeds2.srv
DEPENDENCIES ${MSG_DEPS}
)

install(
  FILES mapping_rules.yaml
  DESTINATION share/${PROJECT_NAME})

ament_export_dependencies(rosidl_default_runtime)

ament_package()

ROS2 package.xml

<?xml version="1.0" encoding="UTF-8"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>example_interfaces</name>
  <version>0.0.1</version>
  <description>
    This pacakge contains a single service to demonstrate a bug in the ros1_bridge
  </description>
  <maintainer email="joshua.raanan@gmail.com">Joshua Ra'anan</maintainer>

  <license>BSD</license>
  
  <buildtool_depend>ament_cmake</buildtool_depend>

  <depend>std_msgs</depend>

  <buildtool_depend>rosidl_default_generators</buildtool_depend>
  <exec_depend>rosidl_default_runtime</exec_depend>

  <member_of_group>rosidl_interface_packages</member_of_group>

  <export>
    <build_type>ament_cmake</build_type>
    <ros1_bridge mapping_rules="mapping_rules.yaml"/>
  </export>

</package>

ROS2 mapping_rules.yaml

-
    ros1_package_name: "example_interfaces"
    ros1_service_name: "CustomServiceSucceeds1"
    ros2_package_name: "example_interfaces"
    ros2_service_name: "CustomServiceSucceeds2"
-
    ros1_package_name: "example_interfaces"
    ros1_service_name: "CustomServiceFails"
    ros2_package_name: "example_interfaces"
    ros2_service_name: "CustomServiceFails"
    request_fields_1_to_2:
        same_field_name: "same_field_name"
    response_fields_1_to_2:
        differentFieldName: "different_field_name"

ROS2 CustomServiceFails.srv

float64 same_field_name
---
float64 different_field_name

ROS2 CustomServiceSucceeds2.srv

float64 fine_name
---
float64 also_fine_name

The build instructions are the default instructions:

cd . <ros1-workspace-path>/
. /opt/ros/noetic/setup.bash
catkin build
cd . <ros2-workspace-path>/
. /opt/ros/noetic/setup.bash
colcon build
. <ros1-workspace-path>/example_interfaces/devel/setup.bash
. <ros2-workspace-path>/example_interfaces/install/local_setup.bash
colcon build --packages-select ros1_bridge --cmake-force-configure

Checking the --print-pairs shows that the CustomServiceFails.srv is not mapped.

Expected behavior

The expected behavior is that both example_interfaces/CustomServiceSucceeds and example_interfaces/CustomServiceFails are bridged.

Actual behavior

What actually happens is that only example_interfaces/CustomServiceSucceeds is bridged and example_interfaces/CustomServiceFails is not bridged.

Supported ROS 2 <=> ROS 1 service type conversion pairs:
  - 'diagnostic_msgs/srv/AddDiagnostics' (ROS 2) <=> 'diagnostic_msgs/AddDiagnostics' (ROS 1)
  - 'diagnostic_msgs/srv/SelfTest' (ROS 2) <=> 'diagnostic_msgs/SelfTest' (ROS 1)
  - 'example_interfaces/srv/CustomServiceSucceeds2' (ROS 2) <=> 'example_interfaces/CustomServiceSucceeds1' (ROS 1)
  - 'gazebo_msgs/srv/BodyRequest' (ROS 2) <=> 'gazebo_msgs/BodyRequest' (ROS 1)

Additional information

First things first: apologies for disappointing, but I am not bringing a solution to your problem.

I have stumbled on the same issue. I have two service definitions that use the same type but due to the ROS2 naming convention the names themselves deffer. I set up the mapping_rules accordingly but there was no result. I did some additional digging and I think that I found the issue.

Line number 612 in init.py states:

if (ros1_type, ros2_type) not in message_string_pairs:
     match = False
     break

In my case ros1_type & ros2_type are both uint8 but because they are compared to a member of message_string_pairs that is ('std_msgs/UInt8', 'std_msgs/UInt8') this check fails.

Here is the snippet from the .srv files.
ROS1 Service

...
uint8 outputNr 
...

ROS2 Service

...
uint8 output_nr 
...

And the snippet from the mapping_rules:

...
request_fields_1_to_2:
    outputNr: "output_nr"
...

I have not yet investigated the solution but I think the issue resides there. Developers, please let me know if I am barking at the wrong tree or if I there is some sense here.

@tgaspar

I'd like to contribute to this issue. If you don't mind, could you help review #293?

@tgaspar said:

I have not yet investigated the solution but I think the issue resides there. Developers, please let me know if I am barking at the wrong tree or if I there is some sense here.

I can attest to this. I am working on #256 and realized the mappings for actions wasn't working since I used the same logic.

I solved it for #256 in b1800c4. Please review. It should be applicable for services as well.

@ipa-hsd

After using your ipa-hsd:action_bridge with latest commit to build ros1_bridge, it generates the service source code, e.g. build/ros1_bridge/generated/test_example_interfaces__srv__CustomServiceFails__factories.cpp,

<omited code>

std::unique_ptr<ActionFactoryInterface>
get_action_factory_test_example_interfaces__srv__CustomServiceFails(const std::string & ros_id, const std::string & package_name, const std::string & action_name)
{
  (void)ros_id;
  (void)package_name;
  (void)action_name;
  return nullptr;
}
// conversion functions for available interfaces

}  // namespace ros1_bridge


but we expect to generate the source code as following

<omited code>

std::unique_ptr<ServiceFactoryInterface>
get_service_factory_test_example_interfaces__srv__CustomServiceFails(const std::string & ros_id, const std::string & package_name, const std::string & service_name)
{
  if (
    (
      ros_id == "ros1" &&
      package_name == "test_example_interfaces" &&
      service_name == "CustomServiceFails"
    ) || (
      ros_id == "ros2" &&
      package_name == "test_example_interfaces" &&
      service_name == "srv/CustomServiceFails"
    )
  ) {
    return std::unique_ptr<ServiceFactoryInterface>(new ServiceFactory<
      test_example_interfaces::CustomServiceFails,
      test_example_interfaces::srv::CustomServiceFails
    >);
  }
  return nullptr;
}
// conversion functions for available interfaces

template <>
void ServiceFactory<
  test_example_interfaces::CustomServiceFails,
  test_example_interfaces::srv::CustomServiceFails
>::translate_1_to_2(
  const test_example_interfaces::CustomServiceFails::Request& req1,
  test_example_interfaces::srv::CustomServiceFails::Request& req2
) {
  auto & same_field_name1 = req1.same_field_name;
  auto & same_field_name2 = req2.same_field_name;
  same_field_name2 = same_field_name1;
}

template <>
void ServiceFactory<
  test_example_interfaces::CustomServiceFails,
  test_example_interfaces::srv::CustomServiceFails
>::translate_1_to_2(
  const test_example_interfaces::CustomServiceFails::Response& req1,
  test_example_interfaces::srv::CustomServiceFails::Response& req2
) {
  auto & differentFieldName1 = req1.differentFieldName;
  auto & different_field_name2 = req2.different_field_name;
  different_field_name2 = differentFieldName1;
}

template <>
void ServiceFactory<
  test_example_interfaces::CustomServiceFails,
  test_example_interfaces::srv::CustomServiceFails
>::translate_2_to_1(
  const test_example_interfaces::srv::CustomServiceFails::Request& req2,
  test_example_interfaces::CustomServiceFails::Request& req1
) {
  auto & same_field_name1 = req1.same_field_name;
  auto & same_field_name2 = req2.same_field_name;
  same_field_name1 = same_field_name2;
}

template <>
void ServiceFactory<
  test_example_interfaces::CustomServiceFails,
  test_example_interfaces::srv::CustomServiceFails
>::translate_2_to_1(
  const test_example_interfaces::srv::CustomServiceFails::Response& req2,
  test_example_interfaces::CustomServiceFails::Response& req1
) {
  auto & differentFieldName1 = req1.differentFieldName;
  auto & different_field_name2 = req2.different_field_name;
  differentFieldName1 = different_field_name2;
}

Could you check it? If you'd like to fix this issue on your PR, I'll close mine.

I haven't solved this for services but only for actions. This is the mapping rule I have:

  ros1_package_name: 'actionlib_tutorials'
  ros1_action_name: 'Fibonacci'
  ros2_package_name: 'action_tutorials_interfaces'
  ros2_action_name: 'Fibonacci'
  feedback_fields_1_to_2:
    sequence: 'partial_sequence'

and this is the generated file:

// generated from ros1_bridge/resource/interface_factories.cpp.em

#include "action_tutorials_interfaces_factories.hpp"

#include <algorithm>

#include "rclcpp/rclcpp.hpp"

// include builtin interfaces
#include <ros1_bridge/convert_builtin_interfaces.hpp>

// include ROS 1 services

// include ROS 2 services

// include ROS 1 actions
#include <actionlib_tutorials/FibonacciAction.h>

// include ROS 2 actions
#include <action_tutorials_interfaces/action/fibonacci.hpp>

namespace ros1_bridge
{

std::shared_ptr<FactoryInterface>
get_factory_action_tutorials_interfaces__action__Fibonacci(const std::string & ros1_type_name, const std::string & ros2_type_name)
{
  (void)ros1_type_name;
  (void)ros2_type_name;
  return std::shared_ptr<FactoryInterface>();
}

std::unique_ptr<ServiceFactoryInterface>
get_service_factory_action_tutorials_interfaces__action__Fibonacci(const std::string & ros_id, const std::string & package_name, const std::string & service_name)
{
  (void)ros_id;
  (void)package_name;
  (void)service_name;
  return nullptr;
}

std::unique_ptr<ActionFactoryInterface>
get_action_factory_action_tutorials_interfaces__action__Fibonacci(const std::string & ros_id, const std::string & package_name, const std::string & action_name)
{
  if (
    ros_id == "ros1" &&
    package_name == "actionlib_tutorials" &&
    action_name == "Fibonacci"
  ) {
    return std::unique_ptr<ActionFactoryInterface>(new ActionFactory_2_1<
      actionlib_tutorials::FibonacciAction,
      action_tutorials_interfaces::action::Fibonacci
    >);
  }
  else if
    (
      ros_id == "ros2" &&
      package_name == "action_tutorials_interfaces" &&
      action_name == "action/Fibonacci"
  ) {
    return std::unique_ptr<ActionFactoryInterface>(new ActionFactory_1_2<
      actionlib_tutorials::FibonacciAction,
      action_tutorials_interfaces::action::Fibonacci
    >);
  }
  return nullptr;
}
// conversion functions for available interfaces

template <>
void ActionFactory_1_2<
actionlib_tutorials::FibonacciAction,
action_tutorials_interfaces::action::Fibonacci
>::translate_goal_1_to_2(
  const ROS1Goal &goal1,
  ROS2Goal &goal2)
{
  auto & order1 = goal1.order;
  auto & order2 = goal2.order;
    order2 = order1;

}

template <>
void ActionFactory_2_1<
actionlib_tutorials::FibonacciAction,
action_tutorials_interfaces::action::Fibonacci
>::translate_result_1_to_2(
  ROS2Result &result2,
  const ROS1Result &result1)
{
  result2.sequence.resize(result1.sequence.size());
  auto sequence1_it = result1.sequence.begin();
  auto sequence2_it = result2.sequence.begin();
  while (
    sequence1_it != result1.sequence.end() &&
    sequence2_it != result2.sequence.end()
  ) {
    auto & sequence1 = *(sequence1_it++);
    auto & sequence2 = *(sequence2_it++);
    sequence2 = sequence1;
  }

}

template <>
void ActionFactory_2_1<
actionlib_tutorials::FibonacciAction,
action_tutorials_interfaces::action::Fibonacci
>::translate_feedback_1_to_2(
  ROS2Feedback &feedback2,
  const ROS1Feedback &feedback1)
{
  feedback2.partial_sequence.resize(feedback1.sequence.size());
  auto sequence1_it = feedback1.sequence.begin();
  auto partial_sequence2_it = feedback2.partial_sequence.begin();
  while (
    sequence1_it != feedback1.sequence.end() &&
    partial_sequence2_it != feedback2.partial_sequence.end()
  ) {
    auto & sequence1 = *(sequence1_it++);
    auto & partial_sequence2 = *(partial_sequence2_it++);
    partial_sequence2 = sequence1;
  }

}


template <>
void ActionFactory_2_1<
actionlib_tutorials::FibonacciAction,
action_tutorials_interfaces::action::Fibonacci
>::translate_goal_2_to_1(
  const ROS2Goal &goal2,
  ROS1Goal &goal1)
{
  auto & order2 = goal2.order;
  auto & order1 = goal1.order;
    order1 = order2;

}

template <>
void ActionFactory_1_2<
actionlib_tutorials::FibonacciAction,
action_tutorials_interfaces::action::Fibonacci
>::translate_result_2_to_1(
  ROS1Result &result1,
  const ROS2Result &result2)
{
  result1.sequence.resize(result2.sequence.size());
  auto sequence2_it = result2.sequence.begin();
  auto sequence1_it = result1.sequence.begin();
  while (
    sequence2_it != result2.sequence.end() &&
    sequence1_it != result1.sequence.end()
  ) {
    auto & sequence2 = *(sequence2_it++);
    auto & sequence1 = *(sequence1_it++);
    sequence1 = sequence2;
  }

}

template <>
void ActionFactory_1_2<
actionlib_tutorials::FibonacciAction,
action_tutorials_interfaces::action::Fibonacci
>::translate_feedback_2_to_1(
  ROS1Feedback &feedback1,
  const ROS2Feedback &feedback2)
{
  feedback1.sequence.resize(feedback2.partial_sequence.size());
  auto partial_sequence2_it = feedback2.partial_sequence.begin();
  auto sequence1_it = feedback1.sequence.begin();
  while (
    partial_sequence2_it != feedback2.partial_sequence.end() &&
    sequence1_it != feedback1.sequence.end()
  ) {
    auto & partial_sequence2 = *(partial_sequence2_it++);
    auto & sequence1 = *(sequence1_it++);
    sequence1 = partial_sequence2;
  }

}



}  // namespace ros1_bridge

I will extend this for services as well and then you could check again.

There is a logical error in my code, which got exposed while doing the mapping for services. I will fix it and push in new commits in #256

cdb4795 should fix it. @iuhilnehc-ynos could you please check it?

@ipa-hsd

Good, I just quickly try you commit cdb4795 to build ros1_bridge, but it failed as follows,

mapping_rules.yaml

-
    ros1_package_name: 'test_example_interfaces'
    ros1_service_name: 'CustomServiceFails'
    ros2_package_name: 'test_example_interfaces'
    ros2_service_name: 'CustomServiceFails'
    request_fields_1_to_2:
        same_field_name: 'same_field_name'
    response_fields_1_to_2:
        differentFieldName: 'different_field_name'

build log for ros1_bridge

/home/chenlh/Desktop/ros1_bridge_issue_285/ros1_bridge_ws/build/ros1_bridge/generated/test_example_interfaces__srv__CustomServiceFails__factories.cpp: In member function ‘void ros1_bridge::ServiceFactory<ROS1_T, ROS2_T>::translate_2_to_1(const ROS2Response&, ros1_bridge::ServiceFactory<ROS1_T, ROS2_T>::ROS1Response&) [with ROS1_T = test_example_interfaces::CustomServiceFails; ROS2_T = test_example_interfaces::srv::CustomServiceFails; ros1_bridge::ServiceFactory<ROS1_T, ROS2_T>::ROS2Response = test_example_interfaces::srv::CustomServiceFails_Response_<std::allocator<void> >; ros1_bridge::ServiceFactory<ROS1_T, ROS2_T>::ROS1Response = test_example_interfaces::CustomServiceFailsResponse_<std::allocator<void> >]’:
/home/chenlh/Desktop/ros1_bridge_issue_285/ros1_bridge_ws/build/ros1_bridge/generated/test_example_interfaces__srv__CustomServiceFails__factories.cpp:114:3: error: ‘different_field_name1’ was not declared in this scope; did you mean ‘different_field_name2’?
  114 |   different_field_name1 = differentFieldName2;
      |   ^~~~~~~~~~~~~~~~~~~~~
      |   different_field_name2
/home/chenlh/Desktop/ros1_bridge_issue_285/ros1_bridge_ws/build/ros1_bridge/generated/test_example_interfaces__srv__CustomServiceFails__factories.cpp:114:27: error: ‘differentFieldName2’ was not declared in this scope; did you mean ‘differentFieldName1’?
  114 |   different_field_name1 = differentFieldName2;
      |                           ^~~~~~~~~~~~~~~~~~~
      |                           differentFieldName1

generated source

104 template <>
105 void ServiceFactory<
106   test_example_interfaces::CustomServiceFails,
107   test_example_interfaces::srv::CustomServiceFails
108 >::translate_2_to_1(
109   const test_example_interfaces::srv::CustomServiceFails::Response& req2,
110   test_example_interfaces::CustomServiceFails::Response& req1
111 ) {
112   auto & differentFieldName1 = req1.differentFieldName;
113   auto & different_field_name2 = req2.different_field_name;
114   different_field_name1 = differentFieldName2;
115 }

could you check it again?

Yes there is an error in resource/interface_factories.cpp.em. Will resolve it today.

0746797 builds fine for me. These are the mappings I get:

emplate <>
void ServiceFactory<
  example_interfaces::CustomServiceFails,
  example_interfaces::srv::CustomServiceFails
>::translate_1_to_2(
  const example_interfaces::CustomServiceFails::Request& req1,
  example_interfaces::srv::CustomServiceFails::Request& req2
) {
  auto & same_field_name1 = req1.same_field_name;
  auto & same_field_name2 = req2.same_field_name;
  same_field_name2 = same_field_name1;
}

template <>
void ServiceFactory<
  example_interfaces::CustomServiceFails,
  example_interfaces::srv::CustomServiceFails
>::translate_1_to_2(
  const example_interfaces::CustomServiceFails::Response& req1,
  example_interfaces::srv::CustomServiceFails::Response& req2
) {
  auto & differentFieldName1 = req1.differentFieldName;
  auto & different_field_name2 = req2.different_field_name;
  different_field_name2 = differentFieldName1;
}

template <>
void ServiceFactory<
  example_interfaces::CustomServiceFails,
  example_interfaces::srv::CustomServiceFails
>::translate_2_to_1(
  const example_interfaces::srv::CustomServiceFails::Request& req2,
  example_interfaces::CustomServiceFails::Request& req1
) {
  auto & same_field_name1 = req1.same_field_name;
  auto & same_field_name2 = req2.same_field_name;
  same_field_name1 = same_field_name2;
}

template <>
void ServiceFactory<
  example_interfaces::CustomServiceFails,
  example_interfaces::srv::CustomServiceFails
>::translate_2_to_1(
  const example_interfaces::srv::CustomServiceFails::Response& req2,
  example_interfaces::CustomServiceFails::Response& req1
) {
  auto & differentFieldName1 = req1.differentFieldName;
  auto & different_field_name2 = req2.different_field_name;
  differentFieldName1 = different_field_name2;
}

Bumped into the same issue for services. What is the progress on this?

I spent some hours today fixing this for services since I needed it. I have a branch called fieldnamebug at a forked repo:

https://github.com/tompe17/ros1_bridge

Is this fixed in some other place (I did not see a PR for it) or should I make a pull request of this. There is a small change in the python code and in the template since the template only worked from ros1 to ros2 and not the other way. I am unsure about the intended logic in the Python code that I changed. The code as it is will never work for different field name but same type.

If you have a PR that addresses this bug, please do submit it. We can then review it and (hopefully) get it merged.

@tompe17 in my comment here #285 (comment) I mention that the mapping worked for different field names for services. Maybe I messed up during rebasing. Can you point to the services you are trying to map? I can try it out locally.

@ipa-hsd I did submit my pull request so you can see what I did.

I am not using standard services. The one that first failed for me was the mapping (if you remove JoystickParams it will still fail):

-
  ros1_package_name: 'dji_osdk_ros'
  ros1_service_name: 'FlightTaskControl'
  ros2_package_name: 'ros2_dji_osdk_ros_msgs'
  ros2_service_name: 'FlightTaskControl'
  request_fields_1_to_2:
    task: 'task'
    joystickCommand: 'joystick_command'
    velocityControlTimeMs: 'velocity_control_time_ms'
    posThresholdInM: 'pos_threshold_in'
    yawThresholdInDeg: 'yaw_threshold_in_deg'
  response_fields_1_to_2:
    result: 'result'

And the two services:

ROS2;


uint8 TASK_GOHOME = 1
uint8 TASK_POSITION_AND_YAW_CONTROL   = 2
uint8 TASK_GOHOME_AND_CONFIRM_LANDING = 3
uint8 TASK_TAKEOFF = 4
uint8 TASK_VELOCITY_AND_YAWRATE_CONTROL = 5
uint8 TASK_LAND          = 6
uint8 START_MOTOR        = 7
uint8 STOP_MOTOR         = 8
uint8 TASK_EXIT_GO_HOME  = 12
uint8 TASK_EXIT_LANDING  = 14
uint8 TASK_FORCE_LANDING_AVOID_GROUND = 30 #/*!< confirm landing */
uint8 TASK_FORCE_LANDING              = 31 #/*!< force landing */

uint8 task # see constants above for possible tasks
JoystickParams joystick_command #Provide Position and Velocity control
uint32 velocity_control_time_ms #Velocity control time
float32 pos_threshold_in #(Meter)
float32 yaw_threshold_in_deg #(Degree)
---
bool result 

ROS1:


#constant for tasks
uint8 TASK_GOHOME = 1
uint8 TASK_POSITION_AND_YAW_CONTROL   = 2
uint8 TASK_GOHOME_AND_CONFIRM_LANDING = 3
uint8 TASK_TAKEOFF = 4
uint8 TASK_VELOCITY_AND_YAWRATE_CONTROL = 5
uint8 TASK_LAND          = 6
uint8 START_MOTOR        = 7
uint8 STOP_MOTOR         = 8
uint8 TASK_EXIT_GO_HOME  = 12
uint8 TASK_EXIT_LANDING  = 14
uint8 TASK_FORCE_LANDING_AVOID_GROUND = 30 #/*!< confirm landing */
uint8 TASK_FORCE_LANDING              = 31 #/*!< force landing */

#request
uint8 task    # see constants above for possible tasks
JoystickParams joystickCommand  #Provide Position and Velocity control
uint32 velocityControlTimeMs    #Velocity control time
float32 posThresholdInM  #(Meter)
float32 yawThresholdInDeg  #(Degree)
---
#response
bool result