Skip to content

Commit

Permalink
fixed RC mode with bumper, + BDD test
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Jan 16, 2025
1 parent b041351 commit f5e70e6
Show file tree
Hide file tree
Showing 8 changed files with 497 additions and 10 deletions.
22 changes: 12 additions & 10 deletions src/control_manager/control_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1844,14 +1844,14 @@ void ControlManager::initialize(void) {
service_server_parachute_ = nh_.advertiseService("parachute_in", &ControlManager::callbackParachute, this);
service_server_set_min_z_ = nh_.advertiseService("set_min_z_in", &ControlManager::callbackSetMinZ, this);
service_server_transform_reference_ = nh_.advertiseService("transform_reference_in", &ControlManager::callbackTransformReference, this);
service_server_transform_reference_array_ = nh_.advertiseService("transform_reference_array_in", &ControlManager::callbackTransformReferenceArray, this);
service_server_transform_reference_array_ = nh_.advertiseService("transform_reference_array_in", &ControlManager::callbackTransformReferenceArray, this);
service_server_transform_pose_ = nh_.advertiseService("transform_pose_in", &ControlManager::callbackTransformPose, this);
service_server_transform_vector3_ = nh_.advertiseService("transform_vector3_in", &ControlManager::callbackTransformVector3, this);
service_server_bumper_enabler_ = nh_.advertiseService("bumper_in", &ControlManager::callbackEnableBumper, this);
service_server_get_min_z_ = nh_.advertiseService("get_min_z_in", &ControlManager::callbackGetMinZ, this);
service_server_validate_reference_ = nh_.advertiseService("validate_reference_in", &ControlManager::callbackValidateReference, this);
service_server_validate_reference_2d_ = nh_.advertiseService("validate_reference_2d_in", &ControlManager::callbackValidateReference2d, this);
service_server_validate_reference_array_ = nh_.advertiseService("validate_reference_array_in", &ControlManager::callbackValidateReferenceArray, this);
service_server_validate_reference_array_ = nh_.advertiseService("validate_reference_array_in", &ControlManager::callbackValidateReferenceArray, this);
service_server_start_trajectory_tracking_ = nh_.advertiseService("start_trajectory_tracking_in", &ControlManager::callbackStartTrajectoryTracking, this);
service_server_stop_trajectory_tracking_ = nh_.advertiseService("stop_trajectory_tracking_in", &ControlManager::callbackStopTrajectoryTracking, this);
service_server_resume_trajectory_tracking_ = nh_.advertiseService("resume_trajectory_tracking_in", &ControlManager::callbackResumeTrajectoryTracking, this);
Expand Down Expand Up @@ -3168,7 +3168,7 @@ void ControlManager::timerJoystick(const ros::TimerEvent& event) {
}
}

if (rc_goto_active_ && last_tracker_cmd && sh_hw_api_rc_.hasMsg()) {
if (rc_goto_active_ && !bumper_repulsing_ && last_tracker_cmd && sh_hw_api_rc_.hasMsg()) {

// create the reference
mrs_msgs::VelocityReferenceStampedSrv::Request request;
Expand Down Expand Up @@ -3285,8 +3285,11 @@ void ControlManager::timerBumper(const ros::TimerEvent& event) {
return;
}

if (!isFlyingNormally() && !bumper_repulsing_) {
return;
if (!isFlyingNormally()) {
if (!(bumper_repulsing_ || rc_goto_active_)) {
ROS_WARN_THROTTLE(1.0, "[ControlManager]: bumpper can not function, not flying 'normally'");
return;
}
}

if (!got_uav_state_) {
Expand Down Expand Up @@ -5009,14 +5012,14 @@ bool ControlManager::callbackTransformReferenceArray(mrs_msgs::TransformReferenc
}
const auto tf = tf_opt.value();

res.array.header.stamp = req.array.header.stamp;
res.array.header.stamp = req.array.header.stamp;
res.array.header.frame_id = req.to_frame_id;
res.array.array.reserve(req.array.array.size());

for (const auto& ref : req.array.array) {

mrs_msgs::ReferenceStamped ref_stamped;
ref_stamped.header = req.array.header;
ref_stamped.header = req.array.header;
ref_stamped.reference = ref;

if (auto ret = transformer_->transform(ref_stamped, tf)) {
Expand All @@ -5029,11 +5032,10 @@ bool ControlManager::callbackTransformReferenceArray(mrs_msgs::TransformReferenc
res.success = false;
return true;
}

}

res.message = "transformation successful";
res.success = true;
res.message = "transformation successful";
res.success = true;
return true;
}

Expand Down
2 changes: 2 additions & 0 deletions test/control_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ add_subdirectory(rc_remote_control)

add_subdirectory(bumper)

add_subdirectory(bumper_with_rc_remote)

add_subdirectory(trajectory_topic)

add_subdirectory(trajectory_start_stop_resume)
Expand Down
16 changes: 16 additions & 0 deletions test/control_manager/bumper_with_rc_remote/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
get_filename_component(TEST_NAME "${CMAKE_CURRENT_SOURCE_DIR}" NAME)

catkin_add_executable_with_gtest(test_${TEST_NAME}
test.cpp
)

target_link_libraries(test_${TEST_NAME}
${catkin_LIBRARIES}
)

add_dependencies(test_${TEST_NAME}
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)

add_rostest(${TEST_NAME}.test)
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
<launch>

<arg name="this_path" default="$(dirname)" />

<arg name="UAV_NAME" default="uav1" />
<arg name="UAV_TYPE" default="x500" />

<!-- automatically deduce the test name -->
<arg name="test_name" default="$(eval arg('this_path').split('/')[-1])" />

<!-- automatically deduce the package name -->
<arg name="import_eval" default="eval('_' + '_import_' + '_')"/>
<arg name="package_eval" default="eval(arg('import_eval') + '(\'rospkg\')').get_package_name(arg('this_path'))" />
<arg name="package" default="$(eval eval(arg('package_eval')))" />

<include file="$(find mrs_uav_testing)/launch/mrs_simulator.launch">
<arg name="UAV_NAME" default="$(arg UAV_NAME)" />
</include>

<include file="$(dirname)/launch/hw_api.launch">
<arg name="UAV_NAME" default="$(arg UAV_NAME)" />
</include>

<include file="$(find mrs_uav_testing)/launch/mrs_uav_system.launch">
<arg name="automatic_start" default="false" />
<arg name="platform_config" default="$(find mrs_multirotor_simulator)/config/mrs_uav_system/$(arg UAV_TYPE).yaml" />
<arg name="custom_config" default="$(dirname)/config/custom_config.yaml" />
<arg name="world_config" default="$(dirname)/config/world_config.yaml" />
<arg name="UAV_NAME" default="$(arg UAV_NAME)" />
</include>

<test pkg="$(arg package)" type="test_$(arg test_name)" test-name="$(arg test_name)" time-limit="60.0">
<param name="test" value="$(arg test_name)" />
<param name="uav_name" value="$(arg UAV_NAME)" />

<rosparam file="$(find mrs_uav_managers)/config/public/control_manager.yaml" command="load" />
</test>

</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
mrs_uav_managers:

estimation_manager:

state_estimators: [
"gps_baro",
]

initial_state_estimator: "gps_baro"

constraint_manager:

default_constraints:
gps_garmin: "medium"
gps_baro: "medium"

control_manager:

rc_joystick:

enabled: true
# activation channel
channel_number: 6 # indexed from 0

horizontal_speed: 4.00 # [m/s]
vertical_speed: 4.00 # [m/s]
heading_rate: 1.00 # [rad/s]
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
world_origin:

units: "LATLON" # {"UTM, "LATLON"}

origin_x: 47.397743
origin_y: 8.545594

safety_area:

enabled: false

horizontal:

# the frame of reference in which the points are expressed
frame_name: "world_origin"

# polygon
#
# x, y [m] for any frame_name except latlon_origin
# x = latitude, y = longitude [deg] for frame_name=="latlon_origin"
points: [
-50, -50,
50, -50,
50, 50,
-50, 50,
]

vertical:

# the frame of reference in which the max&min z is expressed
frame_name: "world_origin"

max_z: 15.0
min_z: 0.5
66 changes: 66 additions & 0 deletions test/control_manager/bumper_with_rc_remote/launch/hw_api.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
<launch>

<!-- args corresponding to environment variables -->
<arg name="UAV_NAME" default="$(optenv UAV_NAME)" />
<arg name="LOGGER_DEBUG" default="$(optenv LOGGER_DEBUG false)" />
<arg name="RUN_TYPE" default="$(optenv RUN_TYPE uav)" />

<!-- other args -->
<arg name="debug" default="false" />
<arg name="bond" default="$(optenv BOND true)" />
<arg name="nodelet_manager_name" default="$(optenv NODELET_MANAGER)" />
<arg name="custom_config" default="" />

<arg if="$(eval arg('nodelet_manager_name') != '')" name="standalone" value="false" />
<arg if="$(eval arg('nodelet_manager_name') == '')" name="standalone" value="true" />

<env name="ROSCONSOLE_CONFIG_FILE" if="$(eval arg('LOGGER_DEBUG'))" value="$(find mrs_uav_hw_api)/config/debug_verbosity.yaml" />

<arg if="$(arg bond)" name="bond_suffix" value="" />
<arg unless="$(arg bond)" name="bond_suffix" value="--no-bond" />

<arg if="$(eval arg('standalone') or arg('debug'))" name="nodelet" value="standalone" />
<arg unless="$(eval arg('standalone') or arg('debug'))" name="nodelet" value="load" />
<arg if="$(eval arg('standalone') or arg('debug'))" name="nodelet_manager" value="" />
<arg unless="$(eval arg('standalone') or arg('debug'))" name="nodelet_manager" value="$(arg nodelet_manager_name)" />

<arg if="$(arg debug)" name="launch_prefix" value="debug_roslaunch" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />

<group ns="$(arg UAV_NAME)">

<node pkg="nodelet" type="nodelet" name="hw_api" args="$(arg nodelet) mrs_uav_hw_api/HwApiManager $(arg nodelet_manager) $(arg bond_suffix)" output="screen" launch-prefix="$(arg launch_prefix)">

<rosparam file="$(find mrs_uav_hw_api)/config/hw_api.yaml" />
<rosparam file="$(find mrs_multirotor_simulator)/config/hw_api.yaml" />

<!-- Load a user param file -->
<rosparam if="$(eval not arg('custom_config') == '')" file="$(arg custom_config)" />

<!-- Parameters -->
<param name="topic_prefix" type="string" value="/$(arg UAV_NAME)/" />
<param name="uav_name" type="string" value="$(arg UAV_NAME)" />
<param name="simulation" type="bool" value="$(eval arg('RUN_TYPE') == 'simulation')" />

<!-- custom remaps -->
<remap from="~simulator_imu_in" to="/multirotor_simulator/$(arg UAV_NAME)/imu" />
<remap from="~simulator_odom_in" to="/multirotor_simulator/$(arg UAV_NAME)/odom" />
<remap from="~simulator_rangefinder_in" to="/multirotor_simulator/$(arg UAV_NAME)/rangefinder" />
<remap from="~simulator_actuators_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/actuators_cmd" />
<remap from="~simulator_control_group_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/control_group_cmd" />
<remap from="~simulator_attitude_rate_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/attitude_rate_cmd" />
<remap from="~simulator_attitude_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/attitude_cmd" />
<remap from="~simulator_acceleration_hdg_rate_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/acceleration_hdg_rate_cmd" />
<remap from="~simulator_acceleration_hdg_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/acceleration_hdg_cmd" />
<remap from="~simulator_velocity_hdg_rate_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/velocity_hdg_rate_cmd" />
<remap from="~simulator_velocity_hdg_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/velocity_hdg_cmd" />
<remap from="~simulator_position_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/position_cmd" />
<remap from="~simulator_tracker_cmd_out" to="/multirotor_simulator/$(arg UAV_NAME)/tracker_cmd" />

<remap from="~rc_channels" to="~rc_channels_unused" />

</node>

</group>

</launch>
Loading

0 comments on commit f5e70e6

Please sign in to comment.