mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-01 07:29:32 +00:00
Compare commits
11 Commits
simple-off
...
known_vert
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
a72cb67d03 | ||
|
|
8ac757598d | ||
|
|
25c3f25642 | ||
|
|
4877d0101b | ||
|
|
8fd69e4ea5 | ||
|
|
c3625490b2 | ||
|
|
cf62364ac7 | ||
|
|
c7bf964ea5 | ||
|
|
5ec04bbefa | ||
|
|
275023b455 | ||
|
|
b3b530c1c7 |
@@ -20,7 +20,7 @@ Clover drone is used on a wide range of educational events, including [Copter Ha
|
||||
|
||||
Preconfigured image for Raspberry Pi with installed and configured software, ready to fly, is available [in the Releases section](https://github.com/CopterExpress/clover/releases).
|
||||
|
||||

|
||||

|
||||

|
||||
|
||||
Image features:
|
||||
|
||||
@@ -80,10 +80,11 @@ catkin_python_setup()
|
||||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
|
||||
|
||||
## Generate messages in the 'msg' folder
|
||||
add_message_files(
|
||||
FILES
|
||||
State.msg
|
||||
)
|
||||
# add_message_files(
|
||||
# FILES
|
||||
# Message1.msg
|
||||
# Message2.msg
|
||||
# )
|
||||
|
||||
## Generate services in the 'srv' folder
|
||||
add_service_files(
|
||||
@@ -91,9 +92,6 @@ add_service_files(
|
||||
GetTelemetry.srv
|
||||
Navigate.srv
|
||||
NavigateGlobal.srv
|
||||
SetAltitude.srv
|
||||
SetYaw.srv
|
||||
SetYawRate.srv
|
||||
SetPosition.srv
|
||||
SetVelocity.srv
|
||||
SetAttitude.srv
|
||||
@@ -308,5 +306,4 @@ endif()
|
||||
if (CATKIN_ENABLE_TESTING)
|
||||
find_package(rostest REQUIRED)
|
||||
add_rostest(test/basic.test)
|
||||
add_rostest(test/offboard.test)
|
||||
endif()
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
# - cuts out a central square from the camera image;
|
||||
# - publishes this cropped image to the topic `/cv/center`;
|
||||
# - computes the average color of it;
|
||||
# - prints its name to the console.
|
||||
# - prints its name to the console.
|
||||
|
||||
import rospy
|
||||
import cv2
|
||||
|
||||
@@ -16,8 +16,11 @@ set_attitude = rospy.ServiceProxy('set_attitude', srv.SetAttitude)
|
||||
set_rates = rospy.ServiceProxy('set_rates', srv.SetRates)
|
||||
land = rospy.ServiceProxy('land', Trigger)
|
||||
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=math.nan, speed=0.5, frame_id='body', tolerance=0.2, auto_arm=False):
|
||||
res = navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), yaw_rate=0, speed=0.5, \
|
||||
frame_id='body', tolerance=0.2, auto_arm=False):
|
||||
|
||||
res = navigate(x=x, y=y, z=z, yaw=yaw, yaw_rate=yaw_rate, speed=speed, \
|
||||
frame_id=frame_id, auto_arm=auto_arm)
|
||||
|
||||
if not res.success:
|
||||
return res
|
||||
|
||||
@@ -45,7 +45,7 @@
|
||||
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||
<param name="calc_flow_gyro" value="true"/>
|
||||
<param name="roi_rad" value="0.8"/>
|
||||
<param name="disable_on_vpe" value="true"/>
|
||||
<param name="disable_on_vpe" value="false"/>
|
||||
</node>
|
||||
|
||||
<!-- simplified offboard control -->
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
<launch>
|
||||
<!-- shortcut for running the simulation (`roslaunch clover simulator.launch`) -->
|
||||
<!-- shurtcut for running the simulation (`roslaunch clover simulator.launch`) -->
|
||||
<include file="$(find clover_simulation)/launch/simulator.launch"/>
|
||||
</launch>
|
||||
|
||||
@@ -1,38 +0,0 @@
|
||||
uint8 MODE_NONE = 0
|
||||
uint8 MODE_NAVIGATE = 1
|
||||
uint8 MODE_NAVIGATE_GLOBAL = 2
|
||||
uint8 MODE_POSITION = 3
|
||||
uint8 MODE_VELOCITY = 4
|
||||
uint8 MODE_ATTITUDE = 5
|
||||
uint8 MODE_RATES = 6
|
||||
|
||||
uint8 YAW_MODE_YAW = 0
|
||||
uint8 YAW_MODE_YAW_RATE = 1
|
||||
uint8 YAW_MODE_YAW_TOWARDS = 2
|
||||
|
||||
# type of offboard control
|
||||
uint8 mode
|
||||
uint8 yaw_mode
|
||||
|
||||
# targets
|
||||
float32 x
|
||||
float32 y
|
||||
float32 z
|
||||
float32 speed
|
||||
float32 lat
|
||||
float32 lon
|
||||
float32 vx
|
||||
float32 vy
|
||||
float32 vz
|
||||
float32 roll
|
||||
float32 pitch
|
||||
float32 yaw
|
||||
float32 roll_rate
|
||||
float32 pitch_rate
|
||||
float32 yaw_rate
|
||||
float32 thrust
|
||||
|
||||
# frames of reference
|
||||
string xy_frame_id
|
||||
string z_frame_id
|
||||
string yaw_frame_id
|
||||
@@ -35,8 +35,11 @@ def print_current_map_position():
|
||||
dist = rospy.wait_for_message('rangefinder/range', Range).range
|
||||
print('Map position:\tx={:.1f}\ty={:.1f}\tz={:.1f}\tyaw={:.1f}\tdist={:.2f}'.format(telem.x, telem.y, telem.z, telem.yaw, dist))
|
||||
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=math.nan, speed=0.5, frame_id='body', tolerance=0.2, auto_arm=False):
|
||||
res = navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), yaw_rate=0, speed=0.5, \
|
||||
frame_id='body', tolerance=0.2, auto_arm=False):
|
||||
|
||||
res = navigate(x=x, y=y, z=z, yaw=yaw, yaw_rate=yaw_rate, speed=speed, \
|
||||
frame_id=frame_id, auto_arm=auto_arm)
|
||||
|
||||
if not res.success:
|
||||
return res
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
|
||||
import rospy
|
||||
import math
|
||||
from math import nan, inf
|
||||
from math import nan
|
||||
import signal
|
||||
import sys
|
||||
from clover import srv
|
||||
@@ -15,8 +15,6 @@ rospy.init_node('autotest_flight', disable_signals=True) # disable signals to al
|
||||
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
||||
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
|
||||
navigate_global = handle_response(rospy.ServiceProxy('navigate_global', srv.NavigateGlobal))
|
||||
set_yaw = handle_response(rospy.ServiceProxy('set_yaw', srv.SetYaw))
|
||||
set_yaw_rate = handle_response(rospy.ServiceProxy('set_yaw_rate', srv.SetYawRate))
|
||||
set_position = handle_response(rospy.ServiceProxy('set_position', srv.SetPosition))
|
||||
set_velocity = handle_response(rospy.ServiceProxy('set_velocity', srv.SetVelocity))
|
||||
set_attitude = handle_response(rospy.ServiceProxy('set_attitude', srv.SetAttitude))
|
||||
@@ -30,8 +28,11 @@ def interrupt(sig, frame):
|
||||
|
||||
signal.signal(signal.SIGINT, interrupt)
|
||||
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=nan, speed=0.5, frame_id='body', tolerance=0.2, auto_arm=False):
|
||||
res = navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=nan, yaw_rate=0, speed=0.5, \
|
||||
frame_id='body', tolerance=0.2, auto_arm=False):
|
||||
|
||||
res = navigate(x=x, y=y, z=z, yaw=yaw, yaw_rate=yaw_rate, speed=speed, \
|
||||
frame_id=frame_id, auto_arm=auto_arm)
|
||||
|
||||
if not res.success:
|
||||
return res
|
||||
@@ -68,17 +69,17 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
|
||||
rospy.sleep(2)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Rotate right 90° using set_yaw [enter] ')
|
||||
set_yaw(yaw=-math.pi / 2, frame_id='navigate_target')
|
||||
input('Rotate right 90° [enter] ')
|
||||
navigate(yaw=-math.pi / 2, frame_id='navigate_target')
|
||||
rospy.sleep(3)
|
||||
|
||||
input('Use set_attitude to fly backwards [enter]')
|
||||
set_attitude(roll=0, pitch=-0.3, yaw=0, thrust=0.5, frame_id='body')
|
||||
set_attitude(pitch=-0.3, roll=0, yaw=0, thrust=0.5, frame_id='body')
|
||||
rospy.sleep(0.3)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Use set_attitude to fly right [enter]')
|
||||
set_attitude(roll=0.3, pitch=0, yaw=0, thrust=0.5, frame_id='body')
|
||||
set_attitude(pitch=0, roll=0.3, yaw=0, thrust=0.5, frame_id='body')
|
||||
rospy.sleep(0.5)
|
||||
set_position(frame_id='body')
|
||||
|
||||
@@ -87,13 +88,13 @@ set_rates(roll_rate=1.2, thrust=0.5)
|
||||
rospy.sleep(0.4)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Rotate 360° to the right using set_yaw_rate [enter]')
|
||||
set_yaw_rate(yaw_rate=-1)
|
||||
input('Rotate 360° to the right using yaw_rate [enter]')
|
||||
set_position(x=nan, y=nan, z=nan, frame_id='body', yaw=nan, yaw_rate=-1)
|
||||
rospy.sleep(2 * math.pi)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Return to start point heading forward [enter]')
|
||||
navigate_wait(x=start.x, y=start.y, z=start.z, yaw=inf, speed=1, frame_id='map')
|
||||
input('Return to start point [enter]')
|
||||
navigate_wait(x=start.x, y=start.y, z=start.z, yaw=start.yaw, speed=1, frame_id='map')
|
||||
|
||||
input('Land [enter]')
|
||||
land()
|
||||
|
||||
@@ -23,7 +23,6 @@
|
||||
#include <tf2_ros/static_transform_broadcaster.h>
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
|
||||
#include <std_srvs/Trigger.h>
|
||||
#include <geometry_msgs/PointStamped.h>
|
||||
#include <geometry_msgs/PoseStamped.h>
|
||||
#include <geometry_msgs/TwistStamped.h>
|
||||
#include <geometry_msgs/Vector3Stamped.h>
|
||||
@@ -38,19 +37,14 @@
|
||||
#include <mavros_msgs/State.h>
|
||||
#include <mavros_msgs/StatusText.h>
|
||||
#include <mavros_msgs/ManualControl.h>
|
||||
#include <mavros_msgs/Altitude.h>
|
||||
|
||||
#include <clover/GetTelemetry.h>
|
||||
#include <clover/Navigate.h>
|
||||
#include <clover/NavigateGlobal.h>
|
||||
#include <clover/SetAltitude.h>
|
||||
#include <clover/SetYaw.h>
|
||||
#include <clover/SetYawRate.h>
|
||||
#include <clover/SetPosition.h>
|
||||
#include <clover/SetVelocity.h>
|
||||
#include <clover/SetAttitude.h>
|
||||
#include <clover/SetRates.h>
|
||||
#include <clover/State.h>
|
||||
|
||||
using std::string;
|
||||
using std::isnan;
|
||||
@@ -60,7 +54,6 @@ using namespace clover;
|
||||
using mavros_msgs::PositionTarget;
|
||||
using mavros_msgs::AttitudeTarget;
|
||||
using mavros_msgs::Thrust;
|
||||
using mavros_msgs::Altitude;
|
||||
|
||||
// tf2
|
||||
tf2_ros::Buffer tf_buffer;
|
||||
@@ -88,40 +81,33 @@ bool land_only_in_offboard, nav_from_sp, check_kill_switch;
|
||||
std::map<string, string> reference_frames;
|
||||
|
||||
// Publishers
|
||||
ros::Publisher attitude_pub, attitude_raw_pub, position_pub, position_raw_pub, rates_pub, thrust_pub, state_pub;
|
||||
ros::Publisher attitude_pub, attitude_raw_pub, position_pub, position_raw_pub, rates_pub, thrust_pub;
|
||||
|
||||
// Service clients
|
||||
ros::ServiceClient arming, set_mode;
|
||||
|
||||
// Containers
|
||||
ros::Timer setpoint_timer;
|
||||
tf::Quaternion tq;
|
||||
PoseStamped position_msg;
|
||||
PositionTarget position_raw_msg;
|
||||
//TwistStamped rates_msg;
|
||||
AttitudeTarget att_raw_msg;
|
||||
Thrust thrust_msg;
|
||||
TwistStamped rates_msg;
|
||||
TransformStamped target, setpoint;
|
||||
geometry_msgs::TransformStamped body;
|
||||
geometry_msgs::TransformStamped terrain;
|
||||
|
||||
// State
|
||||
PoseStamped nav_start;
|
||||
PointStamped setpoint_position;
|
||||
PointStamped setpoint_altitude;
|
||||
Vector3Stamped setpoint_velocity;
|
||||
float setpoint_yaw, setpoint_roll, setpoint_pitch;
|
||||
Vector3 setpoint_rates;
|
||||
string yaw_frame_id;
|
||||
float setpoint_thrust;
|
||||
PoseStamped setpoint_position, setpoint_position_transformed;
|
||||
Vector3Stamped setpoint_velocity, setpoint_velocity_transformed;
|
||||
QuaternionStamped setpoint_attitude, setpoint_attitude_transformed;
|
||||
float setpoint_yaw_rate;
|
||||
float nav_speed;
|
||||
float setpoint_lat = NAN, setpoint_lon = NAN;
|
||||
bool busy = false;
|
||||
bool wait_armed = false;
|
||||
bool nav_from_sp_flag = false;
|
||||
|
||||
// Last published
|
||||
PoseStamped setpoint_pose_local;
|
||||
Vector3Stamped setpoint_velocity_local;
|
||||
float yaw_local;
|
||||
|
||||
enum setpoint_type_t {
|
||||
NONE,
|
||||
NAVIGATE,
|
||||
@@ -129,10 +115,7 @@ enum setpoint_type_t {
|
||||
POSITION,
|
||||
VELOCITY,
|
||||
ATTITUDE,
|
||||
RATES,
|
||||
_ALTITUDE,
|
||||
_YAW,
|
||||
_YAW_RATE,
|
||||
RATES
|
||||
};
|
||||
|
||||
enum setpoint_type_t setpoint_type = NONE;
|
||||
@@ -187,7 +170,7 @@ void handleLocalPosition(const PoseStamped& pose)
|
||||
{
|
||||
local_position = pose;
|
||||
publishBodyFrame();
|
||||
// TODO: home?
|
||||
// TODO: terrain?, home?
|
||||
}
|
||||
|
||||
// wait for transform without interrupting publishing setpoints
|
||||
@@ -205,20 +188,6 @@ inline bool waitTransform(const string& target, const string& source,
|
||||
return false;
|
||||
}
|
||||
|
||||
void handleAltitude(const Altitude& alt)
|
||||
{
|
||||
// publish terrain frame
|
||||
if (!std::isfinite(alt.bottom_clearance)) return;
|
||||
// terrain.header.stamp = alt.header.stamp;
|
||||
|
||||
if (!waitTransform(local_frame, body.child_frame_id, alt.header.stamp, ros::Duration(0.1))) return;
|
||||
|
||||
auto t = tf_buffer.lookupTransform(local_frame, body.child_frame_id, alt.header.stamp);
|
||||
t.child_frame_id = terrain.child_frame_id;
|
||||
t.transform.translation.z -= alt.bottom_clearance;
|
||||
static_transform_broadcaster->sendTransform(t);
|
||||
}
|
||||
|
||||
#define TIMEOUT(msg, timeout) (msg.header.stamp.isZero() || (ros::Time::now() - msg.header.stamp > timeout))
|
||||
|
||||
bool getTelemetry(GetTelemetry::Request& req, GetTelemetry::Response& res)
|
||||
@@ -238,11 +207,11 @@ bool getTelemetry(GetTelemetry::Request& req, GetTelemetry::Response& res)
|
||||
res.vx = NAN;
|
||||
res.vy = NAN;
|
||||
res.vz = NAN;
|
||||
res.roll = NAN;
|
||||
res.pitch = NAN;
|
||||
res.roll = NAN;
|
||||
res.yaw = NAN;
|
||||
res.roll_rate = NAN;
|
||||
res.pitch_rate = NAN;
|
||||
res.roll_rate = NAN;
|
||||
res.yaw_rate = NAN;
|
||||
res.voltage = NAN;
|
||||
res.cell_voltage = NAN;
|
||||
@@ -372,20 +341,20 @@ inline float getDistance(const Point& from, const Point& to)
|
||||
return hypot(from.x - to.x, from.y - to.y, from.z - to.z);
|
||||
}
|
||||
|
||||
void getNavigateSetpoint(const ros::Time& stamp, const float speed, Point& nav_setpoint)
|
||||
void getNavigateSetpoint(const ros::Time& stamp, float speed, Point& nav_setpoint)
|
||||
{
|
||||
if (wait_armed) {
|
||||
// don't start navigating if we're waiting arming
|
||||
nav_start.header.stamp = stamp;
|
||||
}
|
||||
|
||||
float distance = getDistance(nav_start.pose.position, setpoint_pose_local.pose.position);
|
||||
float distance = getDistance(nav_start.pose.position, setpoint_position_transformed.pose.position);
|
||||
float time = distance / speed;
|
||||
float passed = std::min((stamp - nav_start.header.stamp).toSec() / time, 1.0);
|
||||
|
||||
nav_setpoint.x = nav_start.pose.position.x + (setpoint_pose_local.pose.position.x - nav_start.pose.position.x) * passed;
|
||||
nav_setpoint.y = nav_start.pose.position.y + (setpoint_pose_local.pose.position.y - nav_start.pose.position.y) * passed;
|
||||
nav_setpoint.z = nav_start.pose.position.z + (setpoint_pose_local.pose.position.z - nav_start.pose.position.z) * passed;
|
||||
nav_setpoint.x = nav_start.pose.position.x + (setpoint_position_transformed.pose.position.x - nav_start.pose.position.x) * passed;
|
||||
nav_setpoint.y = nav_start.pose.position.y + (setpoint_position_transformed.pose.position.y - nav_start.pose.position.y) * passed;
|
||||
nav_setpoint.z = nav_start.pose.position.z + (setpoint_position_transformed.pose.position.z - nav_start.pose.position.z) * passed;
|
||||
}
|
||||
|
||||
PoseStamped globalToLocal(double lat, double lon)
|
||||
@@ -416,101 +385,44 @@ PoseStamped globalToLocal(double lat, double lon)
|
||||
return pose;
|
||||
}
|
||||
|
||||
// publish navigate_target frame
|
||||
void publishTarget(ros::Time stamp, bool _static = false)
|
||||
{
|
||||
bool single_frame = (setpoint_position.header.frame_id == setpoint_altitude.header.frame_id);
|
||||
|
||||
// handle yaw for target frame
|
||||
if (setpoint_yaw_type == YAW || setpoint_yaw_type == YAW_RATE) { // use last set yaw for yaw_rate
|
||||
if (setpoint_altitude.header.frame_id == yaw_frame_id) {
|
||||
target.transform.rotation = tf::createQuaternionMsgFromYaw(setpoint_yaw);
|
||||
} else {
|
||||
single_frame = false;
|
||||
target.transform.rotation = tf::createQuaternionMsgFromYaw(yaw_local);
|
||||
}
|
||||
} else if (setpoint_yaw_type == TOWARDS) {
|
||||
single_frame = false;
|
||||
target.transform.rotation = tf::createQuaternionMsgFromYaw(yaw_local);
|
||||
}
|
||||
|
||||
if (_static && single_frame) {
|
||||
// publish at user's command, if all frames are the same
|
||||
target.header.frame_id = setpoint_position.header.frame_id;
|
||||
target.header.stamp = stamp;
|
||||
target.transform.translation.x = setpoint_position.point.x;
|
||||
target.transform.translation.y = setpoint_position.point.y;
|
||||
target.transform.translation.z = setpoint_position.point.z;
|
||||
|
||||
} else if (!_static) {
|
||||
// publish at each iteration, if frames are different
|
||||
target.header = setpoint_pose_local.header;
|
||||
target.transform.translation.x = setpoint_pose_local.pose.position.x;
|
||||
target.transform.translation.y = setpoint_pose_local.pose.position.y;
|
||||
target.transform.translation.z = setpoint_pose_local.pose.position.z;
|
||||
}
|
||||
|
||||
static_transform_broadcaster->sendTransform(target);
|
||||
}
|
||||
|
||||
void publish(const ros::Time stamp)
|
||||
{
|
||||
if (setpoint_type == NONE) return;
|
||||
|
||||
position_raw_msg.header.stamp = stamp;
|
||||
thrust_msg.header.stamp = stamp;
|
||||
rates_msg.header.stamp = stamp;
|
||||
|
||||
// transform position
|
||||
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
|
||||
setpoint_position.header.stamp = stamp;
|
||||
setpoint_altitude.header.stamp = stamp;
|
||||
// transform xy
|
||||
try {
|
||||
auto xy = tf_buffer.transform(setpoint_position, local_frame, ros::Duration(0.05));
|
||||
setpoint_pose_local.header = xy.header;
|
||||
setpoint_pose_local.pose.position.x = xy.point.x;
|
||||
setpoint_pose_local.pose.position.y = xy.point.y;
|
||||
} catch (tf2::TransformException& ex) {
|
||||
// can't transform xy, use last known
|
||||
ROS_WARN_THROTTLE(10, "can't transform: %s", ex.what());
|
||||
try {
|
||||
// transform position and/or yaw
|
||||
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION || setpoint_type == VELOCITY || setpoint_type == ATTITUDE) {
|
||||
setpoint_position.header.stamp = stamp;
|
||||
tf_buffer.transform(setpoint_position, setpoint_position_transformed, local_frame, ros::Duration(0.05));
|
||||
}
|
||||
// transform altitude
|
||||
try {
|
||||
setpoint_pose_local.pose.position.z = tf_buffer.transform(setpoint_altitude, local_frame, ros::Duration(0.05)).point.z;
|
||||
} catch (tf2::TransformException& ex) {
|
||||
// can't transform altitude, use last known
|
||||
ROS_WARN_THROTTLE(10, "can't transform: %s", ex.what());
|
||||
|
||||
// transform velocity
|
||||
if (setpoint_type == VELOCITY) {
|
||||
setpoint_velocity.header.stamp = stamp;
|
||||
tf_buffer.transform(setpoint_velocity, setpoint_velocity_transformed, local_frame, ros::Duration(0.05));
|
||||
}
|
||||
|
||||
} catch (const tf2::TransformException& e) {
|
||||
ROS_WARN_THROTTLE(10, "can't transform");
|
||||
}
|
||||
|
||||
// transform yaw
|
||||
if (setpoint_yaw_type == YAW) {
|
||||
try {
|
||||
QuaternionStamped q;
|
||||
q.header.stamp = stamp;
|
||||
q.header.frame_id = yaw_frame_id;
|
||||
q.quaternion = tf::createQuaternionMsgFromYaw(setpoint_yaw);
|
||||
yaw_local = tf2::getYaw(tf_buffer.transform(q, local_frame, ros::Duration(0.05)).quaternion);
|
||||
} catch (tf2::TransformException& ex) {
|
||||
// can't transform yaw, use last known
|
||||
ROS_WARN_THROTTLE(10, "can't transform: %s", ex.what());
|
||||
}
|
||||
}
|
||||
|
||||
// compute navigate setpoint
|
||||
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
||||
position_msg.pose.orientation = setpoint_position_transformed.pose.orientation; // copy yaw
|
||||
getNavigateSetpoint(stamp, nav_speed, position_msg.pose.position);
|
||||
|
||||
if (setpoint_yaw_type == TOWARDS) {
|
||||
yaw_local = atan2(position_msg.pose.position.y - nav_start.pose.position.y,
|
||||
position_msg.pose.position.x - nav_start.pose.position.x);
|
||||
double yaw_towards = atan2(position_msg.pose.position.y - nav_start.pose.position.y,
|
||||
position_msg.pose.position.x - nav_start.pose.position.x);
|
||||
position_msg.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, yaw_towards);
|
||||
}
|
||||
|
||||
position_msg.pose.orientation = tf::createQuaternionMsgFromYaw(yaw_local);
|
||||
}
|
||||
|
||||
if (setpoint_type == POSITION) {
|
||||
position_msg = setpoint_pose_local;
|
||||
position_msg.pose.orientation = tf::createQuaternionMsgFromYaw(yaw_local);
|
||||
position_msg = setpoint_position_transformed;
|
||||
}
|
||||
|
||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
||||
@@ -527,14 +439,14 @@ void publish(const ros::Time stamp)
|
||||
PositionTarget::IGNORE_AFY +
|
||||
PositionTarget::IGNORE_AFZ +
|
||||
PositionTarget::IGNORE_YAW;
|
||||
position_raw_msg.yaw_rate = setpoint_rates.z;
|
||||
position_raw_msg.yaw_rate = setpoint_yaw_rate;
|
||||
position_raw_msg.position = position_msg.pose.position;
|
||||
position_raw_pub.publish(position_raw_msg);
|
||||
}
|
||||
|
||||
// publish setpoint frame
|
||||
if (!setpoint.child_frame_id.empty()) {
|
||||
if (setpoint.header.stamp >= position_msg.header.stamp) {
|
||||
if (setpoint.header.stamp == position_msg.header.stamp) {
|
||||
return; // avoid TF_REPEATED_DATA warnings
|
||||
}
|
||||
|
||||
@@ -546,22 +458,9 @@ void publish(const ros::Time stamp)
|
||||
setpoint.header.stamp = position_msg.header.stamp;
|
||||
transform_broadcaster->sendTransform(setpoint);
|
||||
}
|
||||
|
||||
// publish dynamic target frame
|
||||
publishTarget(stamp);
|
||||
}
|
||||
|
||||
if (setpoint_type == VELOCITY) {
|
||||
// transform velocity to local frame
|
||||
setpoint_velocity.header.stamp = stamp;
|
||||
try {
|
||||
setpoint_velocity_local = tf_buffer.transform(setpoint_velocity, local_frame, ros::Duration(0.05));
|
||||
} catch (tf2::TransformException& ex) {
|
||||
// can't transform velocity, use last known
|
||||
ROS_WARN_THROTTLE(10, "can't transform: %s", ex.what());
|
||||
}
|
||||
|
||||
// publish velocity
|
||||
position_raw_msg.type_mask = PositionTarget::IGNORE_PX +
|
||||
PositionTarget::IGNORE_PY +
|
||||
PositionTarget::IGNORE_PZ +
|
||||
@@ -569,22 +468,14 @@ void publish(const ros::Time stamp)
|
||||
PositionTarget::IGNORE_AFY +
|
||||
PositionTarget::IGNORE_AFZ;
|
||||
position_raw_msg.type_mask += setpoint_yaw_type == YAW ? PositionTarget::IGNORE_YAW_RATE : PositionTarget::IGNORE_YAW;
|
||||
position_raw_msg.velocity = setpoint_velocity_local.vector;
|
||||
position_raw_msg.yaw = yaw_local;
|
||||
position_raw_msg.yaw_rate = setpoint_rates.z;
|
||||
position_raw_msg.velocity = setpoint_velocity_transformed.vector;
|
||||
position_raw_msg.yaw = tf2::getYaw(setpoint_position_transformed.pose.orientation);
|
||||
position_raw_msg.yaw_rate = setpoint_yaw_rate;
|
||||
position_raw_pub.publish(position_raw_msg);
|
||||
}
|
||||
|
||||
if (setpoint_type == ATTITUDE) {
|
||||
PoseStamped msg;
|
||||
msg.header.stamp = stamp;
|
||||
msg.header.frame_id = local_frame;
|
||||
msg.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(setpoint_roll, setpoint_pitch, yaw_local);
|
||||
attitude_pub.publish(msg);
|
||||
|
||||
Thrust thrust_msg;
|
||||
thrust_msg.header.stamp = stamp;
|
||||
thrust_msg.thrust = setpoint_thrust;
|
||||
attitude_pub.publish(setpoint_position_transformed);
|
||||
thrust_pub.publish(thrust_msg);
|
||||
}
|
||||
|
||||
@@ -593,12 +484,11 @@ void publish(const ros::Time stamp)
|
||||
// thrust_pub.publish(thrust_msg);
|
||||
// mavros rates topics waits for rates in local frame
|
||||
// use rates in body frame for simplicity
|
||||
AttitudeTarget att_raw_msg;
|
||||
att_raw_msg.header.stamp = stamp;
|
||||
att_raw_msg.header.frame_id = fcu_frame;
|
||||
att_raw_msg.type_mask = AttitudeTarget::IGNORE_ATTITUDE;
|
||||
att_raw_msg.body_rate = setpoint_rates;
|
||||
att_raw_msg.thrust = setpoint_thrust;
|
||||
att_raw_msg.body_rate = rates_msg.twist.angular;
|
||||
att_raw_msg.thrust = thrust_msg.thrust;
|
||||
attitude_raw_pub.publish(att_raw_msg);
|
||||
}
|
||||
}
|
||||
@@ -638,59 +528,10 @@ inline void checkState()
|
||||
throw std::runtime_error("No connection to FCU, https://clover.coex.tech/connection");
|
||||
}
|
||||
|
||||
void publishState()
|
||||
{
|
||||
clover::State msg;
|
||||
msg.mode = setpoint_type;
|
||||
msg.yaw_mode = setpoint_yaw_type;
|
||||
|
||||
if (setpoint_position.header.frame_id.empty()) {
|
||||
msg.x = NAN;
|
||||
msg.y = NAN;
|
||||
msg.z = NAN;
|
||||
} else {
|
||||
msg.x = setpoint_position.point.x;
|
||||
msg.y = setpoint_position.point.y;
|
||||
msg.z = setpoint_altitude.point.z;
|
||||
}
|
||||
|
||||
msg.speed = nav_speed;
|
||||
msg.lat = setpoint_lat;
|
||||
msg.lon = setpoint_lon;
|
||||
msg.vx = setpoint_velocity.vector.x;
|
||||
msg.vy = setpoint_velocity.vector.y;
|
||||
msg.vz = setpoint_velocity.vector.z;
|
||||
msg.roll = setpoint_roll;
|
||||
msg.pitch = setpoint_pitch;
|
||||
msg.yaw = !yaw_frame_id.empty() ? setpoint_yaw : NAN;
|
||||
|
||||
msg.roll_rate = setpoint_rates.x;
|
||||
msg.pitch_rate = setpoint_rates.y;
|
||||
msg.yaw_rate = setpoint_rates.z;
|
||||
msg.thrust = setpoint_thrust;
|
||||
|
||||
if (setpoint_type == VELOCITY) {
|
||||
msg.xy_frame_id = setpoint_velocity.header.frame_id;
|
||||
msg.z_frame_id = setpoint_velocity.header.frame_id;
|
||||
} else {
|
||||
msg.xy_frame_id = setpoint_position.header.frame_id;
|
||||
msg.z_frame_id = setpoint_altitude.header.frame_id;
|
||||
}
|
||||
msg.yaw_frame_id = yaw_frame_id;
|
||||
|
||||
state_pub.publish(msg);
|
||||
}
|
||||
|
||||
inline float safe(float value) {
|
||||
return std::isfinite(value) ? value : 0;
|
||||
}
|
||||
|
||||
#define ENSURE_FINITE(var) { if (!std::isfinite(var)) throw std::runtime_error(#var " argument cannot be NaN or Inf"); }
|
||||
|
||||
#define ENSURE_NON_INF(var) { if (std::isinf(var)) throw std::runtime_error(#var " argument cannot be Inf"); }
|
||||
|
||||
bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, float vy, float vz,
|
||||
float roll, float pitch, float yaw, float roll_rate, float pitch_rate, float yaw_rate, // editorconfig-checker-disable-line
|
||||
float pitch, float roll, float yaw, float pitch_rate, float roll_rate, float yaw_rate, // editorconfig-checker-disable-line
|
||||
float lat, float lon, float thrust, float speed, string frame_id, bool auto_arm, // editorconfig-checker-disable-line
|
||||
uint8_t& success, string& message) // editorconfig-checker-disable-line
|
||||
{
|
||||
@@ -717,40 +558,69 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
auto search = reference_frames.find(frame_id);
|
||||
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
|
||||
|
||||
ENSURE_NON_INF(x);
|
||||
ENSURE_NON_INF(y);
|
||||
ENSURE_NON_INF(z);
|
||||
ENSURE_NON_INF(speed); // TODO: allow inf
|
||||
ENSURE_NON_INF(vx);
|
||||
ENSURE_NON_INF(vy);
|
||||
ENSURE_NON_INF(vz);
|
||||
ENSURE_NON_INF(roll);
|
||||
ENSURE_NON_INF(pitch);
|
||||
ENSURE_NON_INF(roll_rate);
|
||||
ENSURE_NON_INF(pitch_rate);
|
||||
ENSURE_NON_INF(yaw_rate);
|
||||
ENSURE_NON_INF(thrust);
|
||||
// Serve "partial" commands
|
||||
|
||||
if (sp_type == NAVIGATE_GLOBAL) {
|
||||
if (!auto_arm && std::isfinite(yaw) &&
|
||||
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
|
||||
isnan(pitch) && isnan(roll) && isnan(thrust) &&
|
||||
isnan(lat) && isnan(lon)) {
|
||||
// change only the yaw
|
||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
|
||||
if (!waitTransform(setpoint_position.header.frame_id, frame_id, stamp, transform_timeout))
|
||||
throw std::runtime_error("Can't transform from " + frame_id + " to " + setpoint_position.header.frame_id);
|
||||
|
||||
message = "Changing yaw only";
|
||||
|
||||
QuaternionStamped q;
|
||||
q.header.frame_id = frame_id;
|
||||
q.header.stamp = stamp;
|
||||
q.quaternion = tf::createQuaternionMsgFromYaw(yaw); // TODO: pitch=0, roll=0 is not totally correct
|
||||
setpoint_position.pose.orientation = tf_buffer.transform(q, setpoint_position.header.frame_id).quaternion;
|
||||
setpoint_yaw_type = YAW;
|
||||
goto publish_setpoint;
|
||||
} else {
|
||||
throw std::runtime_error("Setting yaw is possible only when position or velocity setpoints active");
|
||||
}
|
||||
}
|
||||
|
||||
if (!auto_arm && std::isfinite(yaw_rate) &&
|
||||
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
|
||||
isnan(pitch) && isnan(roll) && isnan(yaw) && isnan(thrust) &&
|
||||
isnan(lat) && isnan(lon)) {
|
||||
// change only the yaw rate
|
||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
|
||||
message = "Changing yaw rate only";
|
||||
|
||||
setpoint_yaw_type = YAW_RATE;
|
||||
setpoint_yaw_rate = yaw_rate;
|
||||
goto publish_setpoint;
|
||||
} else {
|
||||
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints active");
|
||||
}
|
||||
}
|
||||
|
||||
// Serve normal commands
|
||||
|
||||
if (sp_type == NAVIGATE || sp_type == POSITION) {
|
||||
ENSURE_FINITE(x);
|
||||
ENSURE_FINITE(y);
|
||||
ENSURE_FINITE(z);
|
||||
} else if (sp_type == NAVIGATE_GLOBAL) {
|
||||
ENSURE_FINITE(lat);
|
||||
ENSURE_FINITE(lon);
|
||||
}
|
||||
|
||||
if (isfinite(x) != isfinite(y)) {
|
||||
throw std::runtime_error("x and y can be set only together");
|
||||
}
|
||||
|
||||
if (isfinite(yaw_rate)) {
|
||||
if (sp_type > RATES && setpoint_type == ATTITUDE) {
|
||||
throw std::runtime_error("Yaw rate cannot be set in attitude mode.");
|
||||
}
|
||||
}
|
||||
|
||||
// set_altitude
|
||||
if (sp_type == _ALTITUDE) {
|
||||
if (setpoint_type == VELOCITY || setpoint_type == ATTITUDE || setpoint_type == RATES) {
|
||||
throw std::runtime_error("Altitude cannot be set in velocity, attitude or rates mode.");
|
||||
}
|
||||
ENSURE_FINITE(z);
|
||||
} else if (sp_type == VELOCITY) {
|
||||
ENSURE_FINITE(vx);
|
||||
ENSURE_FINITE(vy);
|
||||
ENSURE_FINITE(vz);
|
||||
} else if (sp_type == ATTITUDE) {
|
||||
ENSURE_FINITE(pitch);
|
||||
ENSURE_FINITE(roll);
|
||||
ENSURE_FINITE(thrust);
|
||||
} else if (sp_type == RATES) {
|
||||
ENSURE_FINITE(pitch_rate);
|
||||
ENSURE_FINITE(roll_rate);
|
||||
ENSURE_FINITE(thrust);
|
||||
}
|
||||
|
||||
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL) {
|
||||
@@ -764,13 +634,20 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
speed = default_speed;
|
||||
}
|
||||
|
||||
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY) {
|
||||
if (yaw_rate != 0 && !std::isnan(yaw))
|
||||
throw std::runtime_error("Yaw value should be NaN for setting yaw rate");
|
||||
|
||||
if (std::isnan(yaw_rate) && std::isnan(yaw))
|
||||
throw std::runtime_error("Both yaw and yaw_rate cannot be NaN");
|
||||
}
|
||||
|
||||
if (sp_type == NAVIGATE_GLOBAL) {
|
||||
if (TIMEOUT(global_position, global_position_timeout))
|
||||
throw std::runtime_error("No global position");
|
||||
}
|
||||
|
||||
// if any value need to be transformed to reference frame
|
||||
if (isfinite(x) || isfinite(y) || isfinite(z) || isfinite(vx) || isfinite(vy) || isfinite(vz) || isfinite(yaw)) {
|
||||
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY || sp_type == ATTITUDE) {
|
||||
// make sure transform from frame_id to reference frame available
|
||||
if (!waitTransform(reference_frame, frame_id, stamp, transform_timeout))
|
||||
throw std::runtime_error("Can't transform from " + frame_id + " to " + reference_frame);
|
||||
@@ -787,26 +664,15 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
auto xy_in_req_frame = tf_buffer.transform(pose_local, frame_id);
|
||||
x = xy_in_req_frame.pose.position.x;
|
||||
y = xy_in_req_frame.pose.position.y;
|
||||
setpoint_lat = lat;
|
||||
setpoint_lon = lon;
|
||||
}
|
||||
|
||||
// Everything fine - switch setpoint type
|
||||
if (sp_type <= RATES) {
|
||||
setpoint_type = sp_type;
|
||||
}
|
||||
setpoint_type = sp_type;
|
||||
|
||||
if (setpoint_type != NAVIGATE && setpoint_type != NAVIGATE_GLOBAL) {
|
||||
if (sp_type != NAVIGATE && sp_type != NAVIGATE_GLOBAL) {
|
||||
nav_from_sp_flag = false;
|
||||
}
|
||||
|
||||
if (auto_arm || setpoint_type == VELOCITY || setpoint_type == ATTITUDE || setpoint_type == RATES) {
|
||||
// invalidate position setpoint
|
||||
setpoint_position.header.frame_id = "";
|
||||
setpoint_altitude.header.frame_id = "";
|
||||
yaw_frame_id = "";
|
||||
}
|
||||
|
||||
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL) {
|
||||
// starting point
|
||||
if (nav_from_sp && nav_from_sp_flag) {
|
||||
@@ -815,139 +681,89 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
} else {
|
||||
nav_start = local_position;
|
||||
}
|
||||
|
||||
if (!isnan(speed)) {
|
||||
nav_speed = speed;
|
||||
}
|
||||
|
||||
nav_speed = speed;
|
||||
nav_from_sp_flag = true;
|
||||
}
|
||||
|
||||
// handle position
|
||||
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
|
||||
// if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY) {
|
||||
// if (std::isnan(yaw) && yaw_rate == 0) {
|
||||
// // keep yaw unchanged
|
||||
// // TODO: this is incorrect, because we need yaw in desired frame
|
||||
// yaw = tf2::getYaw(local_position.pose.orientation);
|
||||
// }
|
||||
// }
|
||||
|
||||
PointStamped desired;
|
||||
desired.header.frame_id = frame_id;
|
||||
desired.header.stamp = stamp;
|
||||
desired.point.x = safe(x);
|
||||
desired.point.y = safe(y);
|
||||
desired.point.z = safe(z);
|
||||
if (sp_type == POSITION || sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == VELOCITY || sp_type == ATTITUDE) {
|
||||
// destination point and/or attitude
|
||||
PoseStamped ps;
|
||||
ps.header.frame_id = frame_id;
|
||||
ps.header.stamp = stamp;
|
||||
ps.pose.position.x = x;
|
||||
ps.pose.position.y = y;
|
||||
ps.pose.position.z = z;
|
||||
ps.pose.orientation.w = 1.0; // Ensure quaternion is always valid
|
||||
|
||||
// transform to reference frame
|
||||
desired = tf_buffer.transform(desired, reference_frame);
|
||||
|
||||
// set horizontal position
|
||||
if (isfinite(x) && isfinite(y)) {
|
||||
setpoint_position = desired;
|
||||
} else if (setpoint_position.header.frame_id.empty()) {
|
||||
// TODO: use transform for current stamp
|
||||
setpoint_position.header = local_position.header;
|
||||
setpoint_position.point = local_position.pose.position;
|
||||
}
|
||||
|
||||
// set altitude
|
||||
if (isfinite(z)) {
|
||||
setpoint_altitude = desired;
|
||||
} else if (setpoint_altitude.header.frame_id.empty()) {
|
||||
setpoint_altitude.header = local_position.header;
|
||||
setpoint_altitude.point = local_position.pose.position;
|
||||
}
|
||||
}
|
||||
|
||||
// handle velocity
|
||||
if (sp_type == VELOCITY) {
|
||||
// TODO: allow setting different modes by altitude and xy
|
||||
Vector3Stamped desired;
|
||||
desired.header.frame_id = frame_id;
|
||||
desired.header.stamp = stamp;
|
||||
desired.vector.x = safe(vx);
|
||||
desired.vector.y = safe(vy);
|
||||
desired.vector.z = safe(vz);
|
||||
|
||||
// transform to reference frame
|
||||
desired = tf_buffer.transform(desired, reference_frame);
|
||||
setpoint_velocity.header = desired.header;
|
||||
|
||||
// set horizontal velocity
|
||||
if (isfinite(vx) && isfinite(vy)) {
|
||||
setpoint_velocity.vector.x = desired.vector.x;
|
||||
setpoint_velocity.vector.y = desired.vector.y;
|
||||
}
|
||||
|
||||
// set vertical velocity
|
||||
if (isfinite(vz)) {
|
||||
setpoint_velocity.vector.z = desired.vector.z;
|
||||
}
|
||||
}
|
||||
|
||||
// handle yaw
|
||||
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY || sp_type == ATTITUDE || sp_type == _YAW) {
|
||||
if (isfinite(yaw)) {
|
||||
setpoint_yaw_type = YAW;
|
||||
QuaternionStamped desired;
|
||||
desired.header.frame_id = frame_id;
|
||||
desired.header.stamp = stamp;
|
||||
desired.quaternion = tf::createQuaternionMsgFromYaw(yaw);
|
||||
|
||||
// transform to reference frame
|
||||
desired = tf_buffer.transform(desired, reference_frame);
|
||||
setpoint_yaw = tf2::getYaw(desired.quaternion);
|
||||
yaw_frame_id = reference_frame;
|
||||
|
||||
} else if (isinf(yaw) && yaw > 0) {
|
||||
if (sp_type == ATTITUDE) {
|
||||
ps.pose.position.x = 0;
|
||||
ps.pose.position.y = 0;
|
||||
ps.pose.position.z = 0;
|
||||
ps.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, yaw);
|
||||
} else if (std::isnan(yaw)) {
|
||||
setpoint_yaw_type = YAW_RATE;
|
||||
setpoint_yaw_rate = yaw_rate;
|
||||
} else if (std::isinf(yaw) && yaw > 0) {
|
||||
// yaw towards
|
||||
setpoint_yaw_type = TOWARDS;
|
||||
|
||||
} else if (yaw_frame_id.empty() || sp_type == _YAW) {
|
||||
// yaw is nan and not set previously OR set_yaw(yaw=nan) was called
|
||||
yaw = 0;
|
||||
setpoint_yaw_rate = 0;
|
||||
} else {
|
||||
setpoint_yaw_type = YAW;
|
||||
setpoint_yaw = tf2::getYaw(local_position.pose.orientation); // set yaw to current yaw
|
||||
yaw_frame_id = local_position.header.frame_id;
|
||||
setpoint_yaw_rate = 0;
|
||||
ps.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
|
||||
}
|
||||
|
||||
tf_buffer.transform(ps, setpoint_position, reference_frame);
|
||||
}
|
||||
|
||||
// handle roll
|
||||
if (isfinite(roll)) {
|
||||
setpoint_roll = roll;
|
||||
if (sp_type == VELOCITY) {
|
||||
Vector3Stamped vel;
|
||||
vel.header.frame_id = frame_id;
|
||||
vel.header.stamp = stamp;
|
||||
vel.vector.x = vx;
|
||||
vel.vector.y = vy;
|
||||
vel.vector.z = vz;
|
||||
tf_buffer.transform(vel, setpoint_velocity, reference_frame);
|
||||
}
|
||||
|
||||
// handle pitch
|
||||
if (isfinite(pitch)) {
|
||||
setpoint_pitch = pitch;
|
||||
if (sp_type == ATTITUDE || sp_type == RATES) {
|
||||
thrust_msg.thrust = thrust;
|
||||
}
|
||||
|
||||
// handle yaw rate
|
||||
if (isfinite(yaw_rate)) {
|
||||
setpoint_yaw_type = YAW_RATE;
|
||||
setpoint_rates.z = yaw_rate;
|
||||
}
|
||||
|
||||
// handle pitch rate
|
||||
if (isfinite(roll_rate)) {
|
||||
setpoint_rates.x = roll_rate;
|
||||
}
|
||||
|
||||
// handle roll rate
|
||||
if (isfinite(pitch_rate)) {
|
||||
setpoint_rates.y = pitch_rate;
|
||||
}
|
||||
|
||||
// handle thrust
|
||||
if (isfinite(thrust)) {
|
||||
setpoint_thrust = thrust;
|
||||
if (sp_type == RATES) {
|
||||
rates_msg.twist.angular.x = roll_rate;
|
||||
rates_msg.twist.angular.y = pitch_rate;
|
||||
rates_msg.twist.angular.z = yaw_rate;
|
||||
}
|
||||
|
||||
wait_armed = auto_arm;
|
||||
|
||||
publish_setpoint:
|
||||
publish(stamp); // calculate initial transformed messages first
|
||||
setpoint_timer.start();
|
||||
|
||||
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
|
||||
publishTarget(stamp, true);
|
||||
// publish target frame
|
||||
if (!target.child_frame_id.empty()) {
|
||||
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
|
||||
target.header.frame_id = setpoint_position.header.frame_id;
|
||||
target.header.stamp = stamp;
|
||||
target.transform.translation.x = setpoint_position.pose.position.x;
|
||||
target.transform.translation.y = setpoint_position.pose.position.y;
|
||||
target.transform.translation.z = setpoint_position.pose.position.z;
|
||||
target.transform.rotation = setpoint_position.pose.orientation;
|
||||
static_transform_broadcaster->sendTransform(target);
|
||||
}
|
||||
}
|
||||
|
||||
publishState();
|
||||
|
||||
if (auto_arm) {
|
||||
offboardAndArm();
|
||||
wait_armed = false;
|
||||
@@ -972,39 +788,27 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
}
|
||||
|
||||
bool navigate(Navigate::Request& req, Navigate::Response& res) {
|
||||
return serve(NAVIGATE, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, NAN, NAN, NAN, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
return serve(NAVIGATE, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
}
|
||||
|
||||
bool navigateGlobal(NavigateGlobal::Request& req, NavigateGlobal::Response& res) {
|
||||
return serve(NAVIGATE_GLOBAL, NAN, NAN, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, NAN, req.lat, req.lon, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
}
|
||||
|
||||
bool setAltitude(SetAltitude::Request& req, SetAltitude::Response& res) {
|
||||
return serve(_ALTITUDE, NAN, NAN, req.z, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.frame_id, false, res.success, res.message);
|
||||
}
|
||||
|
||||
bool setYaw(SetYaw::Request& req, SetYaw::Response& res) {
|
||||
return serve(_YAW, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.frame_id, false, res.success, res.message);
|
||||
}
|
||||
|
||||
bool setYawRate(SetYawRate::Request& req, SetYawRate::Response& res) {
|
||||
return serve(_YAW_RATE, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, NAN, "", false, res.success, res.message);
|
||||
return serve(NAVIGATE_GLOBAL, NAN, NAN, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, req.lat, req.lon, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
}
|
||||
|
||||
bool setPosition(SetPosition::Request& req, SetPosition::Response& res) {
|
||||
return serve(POSITION, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
return serve(POSITION, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
}
|
||||
|
||||
bool setVelocity(SetVelocity::Request& req, SetVelocity::Response& res) {
|
||||
return serve(VELOCITY, NAN, NAN, NAN, req.vx, req.vy, req.vz, NAN, NAN, req.yaw, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
return serve(VELOCITY, NAN, NAN, NAN, req.vx, req.vy, req.vz, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
}
|
||||
|
||||
bool setAttitude(SetAttitude::Request& req, SetAttitude::Response& res) {
|
||||
return serve(ATTITUDE, NAN, NAN, NAN, NAN, NAN, NAN, req.roll, req.pitch, req.yaw, NAN, NAN, NAN, NAN, NAN, req.thrust, NAN, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
return serve(ATTITUDE, NAN, NAN, NAN, NAN, NAN, NAN, req.pitch, req.roll, req.yaw, NAN, NAN, NAN, NAN, NAN, req.thrust, NAN, req.frame_id, req.auto_arm, res.success, res.message);
|
||||
}
|
||||
|
||||
bool setRates(SetRates::Request& req, SetRates::Response& res) {
|
||||
return serve(RATES, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.roll_rate, req.pitch_rate, req.yaw_rate, NAN, NAN, req.thrust, NAN, "", req.auto_arm, res.success, res.message);
|
||||
return serve(RATES, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.pitch_rate, req.roll_rate, req.yaw_rate, NAN, NAN, req.thrust, NAN, "", req.auto_arm, res.success, res.message);
|
||||
}
|
||||
|
||||
bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
@@ -1036,7 +840,9 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
auto start = ros::Time::now();
|
||||
while (ros::ok()) {
|
||||
if (state.mode == "AUTO.LAND") {
|
||||
break;
|
||||
res.success = true;
|
||||
busy = false;
|
||||
return true;
|
||||
}
|
||||
if (ros::Time::now() - start > land_timeout)
|
||||
throw std::runtime_error("Land request timed out");
|
||||
@@ -1045,18 +851,6 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
r.sleep();
|
||||
}
|
||||
|
||||
// stop setpoints and invalidate position setpoint
|
||||
setpoint_timer.stop();
|
||||
setpoint_type = NONE;
|
||||
setpoint_position.header.frame_id = "";
|
||||
setpoint_altitude.header.frame_id = "";
|
||||
yaw_frame_id = "";
|
||||
publishState();
|
||||
|
||||
res.success = true;
|
||||
busy = false;
|
||||
return true;
|
||||
|
||||
} catch (const std::exception& e) {
|
||||
res.message = e.what();
|
||||
ROS_INFO("%s", e.what());
|
||||
@@ -1069,11 +863,6 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
bool release(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
{
|
||||
setpoint_timer.stop();
|
||||
setpoint_type = NONE;
|
||||
setpoint_position.header.frame_id = "";
|
||||
setpoint_altitude.header.frame_id = "";
|
||||
yaw_frame_id = "";
|
||||
publishState();
|
||||
res.success = true;
|
||||
return true;
|
||||
}
|
||||
@@ -1099,7 +888,6 @@ int main(int argc, char **argv)
|
||||
nh_priv.param("check_kill_switch", check_kill_switch, true);
|
||||
nh_priv.param("default_speed", default_speed, 0.5f);
|
||||
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
||||
nh_priv.param<string>("terrain_frame", terrain.child_frame_id, "terrain");
|
||||
nh_priv.getParam("reference_frames", reference_frames);
|
||||
|
||||
// Default reference frames
|
||||
@@ -1135,12 +923,6 @@ int main(int argc, char **argv)
|
||||
auto manual_control_sub = nh.subscribe(mavros + "/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>);
|
||||
auto local_position_sub = nh.subscribe(mavros + "/local_position/pose", 1, &handleLocalPosition);
|
||||
|
||||
ros::Subscriber altitude_sub;
|
||||
if (!body.child_frame_id.empty() && !terrain.child_frame_id.empty()) {
|
||||
terrain.header.frame_id = local_frame;
|
||||
altitude_sub = nh.subscribe(mavros + "/altitude", 1, &handleAltitude);
|
||||
}
|
||||
|
||||
// Setpoint publishers
|
||||
position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
|
||||
position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
|
||||
@@ -1149,16 +931,10 @@ int main(int argc, char **argv)
|
||||
rates_pub = nh.advertise<TwistStamped>(mavros + "/setpoint_attitude/cmd_vel", 1);
|
||||
thrust_pub = nh.advertise<Thrust>(mavros + "/setpoint_attitude/thrust", 1);
|
||||
|
||||
// State publisher
|
||||
state_pub = nh_priv.advertise<clover::State>("state", 1, true);
|
||||
|
||||
// Service servers
|
||||
auto gt_serv = nh.advertiseService("get_telemetry", &getTelemetry);
|
||||
auto na_serv = nh.advertiseService("navigate", &navigate);
|
||||
auto ng_serv = nh.advertiseService("navigate_global", &navigateGlobal);
|
||||
auto sl_serv = nh.advertiseService("set_altitude", &setAltitude);
|
||||
auto ya_serv = nh.advertiseService("set_yaw", &setYaw);
|
||||
auto yr_serv = nh.advertiseService("set_yaw_rate", &setYawRate);
|
||||
auto sp_serv = nh.advertiseService("set_position", &setPosition);
|
||||
auto sv_serv = nh.advertiseService("set_velocity", &setVelocity);
|
||||
auto sa_serv = nh.advertiseService("set_attitude", &setAttitude);
|
||||
@@ -1172,7 +948,7 @@ int main(int argc, char **argv)
|
||||
position_msg.header.frame_id = local_frame;
|
||||
position_raw_msg.header.frame_id = local_frame;
|
||||
position_raw_msg.coordinate_frame = PositionTarget::FRAME_LOCAL_NED;
|
||||
//rates_msg.header.frame_id = fcu_frame;
|
||||
rates_msg.header.frame_id = fcu_frame;
|
||||
|
||||
ROS_INFO("ready");
|
||||
ros::spin();
|
||||
|
||||
@@ -13,11 +13,11 @@ float32 alt
|
||||
float32 vx
|
||||
float32 vy
|
||||
float32 vz
|
||||
float32 roll
|
||||
float32 pitch
|
||||
float32 roll
|
||||
float32 yaw
|
||||
float32 roll_rate
|
||||
float32 pitch_rate
|
||||
float32 roll_rate
|
||||
float32 yaw_rate
|
||||
float32 voltage
|
||||
float32 cell_voltage
|
||||
|
||||
@@ -2,6 +2,7 @@ float32 x
|
||||
float32 y
|
||||
float32 z
|
||||
float32 yaw
|
||||
float32 yaw_rate
|
||||
float32 speed
|
||||
string frame_id
|
||||
bool auto_arm
|
||||
|
||||
@@ -2,6 +2,7 @@ float64 lat
|
||||
float64 lon
|
||||
float32 z
|
||||
float32 yaw
|
||||
float32 yaw_rate
|
||||
float32 speed
|
||||
string frame_id
|
||||
bool auto_arm
|
||||
|
||||
@@ -1,5 +0,0 @@
|
||||
float32 z
|
||||
string frame_id
|
||||
---
|
||||
bool success
|
||||
string message
|
||||
@@ -1,5 +1,5 @@
|
||||
float32 roll
|
||||
float32 pitch
|
||||
float32 roll
|
||||
float32 yaw
|
||||
float32 thrust
|
||||
string frame_id
|
||||
|
||||
@@ -2,6 +2,7 @@ float32 x
|
||||
float32 y
|
||||
float32 z
|
||||
float32 yaw
|
||||
float32 yaw_rate
|
||||
string frame_id
|
||||
bool auto_arm
|
||||
---
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
float32 roll_rate
|
||||
float32 pitch_rate
|
||||
float32 roll_rate
|
||||
float32 yaw_rate
|
||||
float32 thrust
|
||||
bool auto_arm
|
||||
|
||||
@@ -2,6 +2,7 @@ float32 vx
|
||||
float32 vy
|
||||
float32 vz
|
||||
float32 yaw
|
||||
float32 yaw_rate
|
||||
string frame_id
|
||||
bool auto_arm
|
||||
---
|
||||
|
||||
@@ -1,5 +0,0 @@
|
||||
float32 yaw
|
||||
string frame_id
|
||||
---
|
||||
bool success
|
||||
string message
|
||||
@@ -1,4 +0,0 @@
|
||||
float32 yaw_rate
|
||||
---
|
||||
bool success
|
||||
string message
|
||||
@@ -1,402 +0,0 @@
|
||||
import rospy
|
||||
import pytest
|
||||
from pytest import approx
|
||||
import threading
|
||||
import mavros_msgs.msg
|
||||
from geometry_msgs.msg import PoseStamped
|
||||
from clover import srv
|
||||
from clover.msg import State
|
||||
from math import nan, inf
|
||||
import tf2_ros
|
||||
import tf2_geometry_msgs
|
||||
|
||||
@pytest.fixture()
|
||||
def node():
|
||||
return rospy.init_node('offboard_test', anonymous=True)
|
||||
|
||||
@pytest.fixture
|
||||
def tf_buffer():
|
||||
buf = tf2_ros.Buffer()
|
||||
tf2_ros.TransformListener(buf)
|
||||
return buf
|
||||
|
||||
def get_state():
|
||||
return rospy.wait_for_message('/simple_offboard/state', State, timeout=1)
|
||||
|
||||
def get_navigate_target(tf_buffer):
|
||||
target = tf_buffer.lookup_transform('map', 'navigate_target', rospy.get_rostime(), rospy.Duration(1))
|
||||
assert target.child_frame_id == 'navigate_target'
|
||||
return target
|
||||
|
||||
def test_offboard(node, tf_buffer):
|
||||
navigate = rospy.ServiceProxy('navigate', srv.Navigate)
|
||||
set_position = rospy.ServiceProxy('set_position', srv.SetPosition)
|
||||
set_altitude = rospy.ServiceProxy('set_altitude', srv.SetAltitude)
|
||||
set_yaw = rospy.ServiceProxy('set_yaw', srv.SetYaw)
|
||||
set_yaw_rate = rospy.ServiceProxy('set_yaw_rate', srv.SetYawRate)
|
||||
set_velocity = rospy.ServiceProxy('set_velocity', srv.SetVelocity)
|
||||
set_attitude = rospy.ServiceProxy('set_attitude', srv.SetAttitude)
|
||||
set_rates = rospy.ServiceProxy('set_rates', srv.SetRates)
|
||||
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
||||
res = navigate()
|
||||
assert res.success == False
|
||||
assert res.message.startswith('State timeout')
|
||||
|
||||
telem = get_telemetry()
|
||||
assert telem.connected == False
|
||||
|
||||
state_pub = rospy.Publisher('/mavros/state', mavros_msgs.msg.State, latch=True, queue_size=1)
|
||||
state_msg = mavros_msgs.msg.State(mode='OFFBOARD', armed=True)
|
||||
|
||||
def publish_state():
|
||||
r = rospy.Rate(2)
|
||||
while not rospy.is_shutdown():
|
||||
state_msg.header.stamp = rospy.Time.now()
|
||||
state_pub.publish(state_msg)
|
||||
r.sleep()
|
||||
|
||||
# start publishing state
|
||||
threading.Thread(target=publish_state, daemon=True).start()
|
||||
rospy.sleep(0.5)
|
||||
|
||||
telem = get_telemetry()
|
||||
assert telem.connected == False
|
||||
|
||||
res = navigate()
|
||||
assert res.success == False
|
||||
assert res.message.startswith('No connection to FCU')
|
||||
|
||||
state_msg.connected = True
|
||||
rospy.sleep(1)
|
||||
|
||||
telem = get_telemetry()
|
||||
assert telem.connected == True
|
||||
|
||||
res = navigate()
|
||||
assert res.success == False
|
||||
assert res.message.startswith('No local position')
|
||||
|
||||
local_position_pub = rospy.Publisher('/mavros/local_position/pose', PoseStamped, latch=True, queue_size=1)
|
||||
local_position_msg = PoseStamped()
|
||||
local_position_msg.header.frame_id = 'map'
|
||||
local_position_msg.pose.position.x = 1
|
||||
local_position_msg.pose.position.y = 2
|
||||
local_position_msg.pose.position.z = 3
|
||||
local_position_msg.pose.orientation.w = 1
|
||||
|
||||
def publish_local_position():
|
||||
r = rospy.Rate(30)
|
||||
while not rospy.is_shutdown():
|
||||
local_position_msg.header.stamp = rospy.Time.now()
|
||||
local_position_pub.publish(local_position_msg)
|
||||
r.sleep()
|
||||
|
||||
# start publishing local position
|
||||
threading.Thread(target=publish_local_position, daemon=True).start()
|
||||
rospy.sleep(0.5)
|
||||
|
||||
# check body frame
|
||||
body = tf_buffer.lookup_transform('map', 'body', rospy.get_rostime(), rospy.Duration(1))
|
||||
assert body.child_frame_id == 'body'
|
||||
assert body.transform.translation.x == approx(1)
|
||||
assert body.transform.translation.y == approx(2)
|
||||
assert body.transform.translation.z == approx(3)
|
||||
|
||||
res = navigate(x=3, y=2, z=1, frame_id='map')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 3
|
||||
assert state.y == 2
|
||||
assert state.z == 1
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'map'
|
||||
assert state.yaw_frame_id == 'map'
|
||||
target = get_navigate_target(tf_buffer)
|
||||
assert target.header.frame_id == 'map'
|
||||
assert target.transform.translation.x == approx(3)
|
||||
assert target.transform.translation.y == approx(2)
|
||||
assert target.transform.translation.z == approx(1)
|
||||
assert target.transform.rotation.x == 0
|
||||
assert target.transform.rotation.y == 0
|
||||
assert target.transform.rotation.z == 0
|
||||
assert target.transform.rotation.w == 1
|
||||
|
||||
# try to set only the y
|
||||
res = navigate(x=nan, y=1, z=nan)
|
||||
assert res.success == False
|
||||
assert res.message.startswith('x and y can be set only together')
|
||||
|
||||
# set z in body frame
|
||||
res = navigate(x=nan, y=nan, z=1, frame_id='body')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 3
|
||||
assert state.y == 2
|
||||
assert state.z == 4
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'map'
|
||||
assert state.yaw_frame_id == 'map'
|
||||
|
||||
# set xy in test frame
|
||||
res = navigate(x=1, y=2, z=nan, frame_id='test')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 1
|
||||
assert state.y == 2
|
||||
assert state.z == 4
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'test'
|
||||
assert state.z_frame_id == 'map'
|
||||
assert state.yaw_frame_id == 'test'
|
||||
|
||||
# auto_arm should invalidate the setpoint
|
||||
res = navigate(x=nan, y=nan, z=1, frame_id='map', auto_arm=True)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 1
|
||||
assert state.y == 2
|
||||
assert state.z == 1
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'map'
|
||||
assert state.yaw_frame_id == 'map'
|
||||
|
||||
# set_attitude should invalidate the setpoint
|
||||
res = set_attitude()
|
||||
assert res.success == True
|
||||
|
||||
res = navigate(x=5, y=6, z=nan, yaw=nan, frame_id='map')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 5
|
||||
assert state.y == 6
|
||||
assert state.z == 3
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'map'
|
||||
assert state.yaw_frame_id == 'map'
|
||||
|
||||
# test set_altitude
|
||||
res = set_altitude(z=7, frame_id='test')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 5
|
||||
assert state.y == 6
|
||||
assert state.z == 7
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'test'
|
||||
assert state.yaw_frame_id == 'map'
|
||||
|
||||
# test set_yaw
|
||||
res = set_yaw(yaw=0.5, frame_id='test2')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 5
|
||||
assert state.y == 6
|
||||
assert state.z == 7
|
||||
assert state.yaw == 0.5
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'test'
|
||||
assert state.yaw_frame_id == 'test2'
|
||||
|
||||
# test set_yaw_rate
|
||||
res = set_yaw_rate(yaw_rate=2)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
|
||||
assert state.x == 5
|
||||
assert state.y == 6
|
||||
assert state.z == 7
|
||||
assert state.yaw_rate == 2
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'test'
|
||||
|
||||
# navigate(yaw=nan) should keep yaw rate mode
|
||||
res = navigate(x=nan, y=nan, z=nan, yaw=nan)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
|
||||
assert state.x == 5
|
||||
assert state.y == 6
|
||||
assert state.z == 7
|
||||
assert state.yaw_rate == 2
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'test'
|
||||
|
||||
# set_yaw(nan) should change back to yaw mode
|
||||
res = set_yaw(yaw=nan)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_NAVIGATE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.yaw == 0
|
||||
assert state.yaw_frame_id == 'map'
|
||||
|
||||
# test set_position
|
||||
res = set_position(x=nan, y=nan, z=13, yaw=nan, frame_id='test2')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_POSITION
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 5
|
||||
assert state.y == 6
|
||||
assert state.z == 13
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'test2'
|
||||
assert state.yaw_frame_id == 'map'
|
||||
|
||||
# set_altitude should not change the mode
|
||||
res = set_altitude(z=3, frame_id='test')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_POSITION
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 5
|
||||
assert state.y == 6
|
||||
assert state.z == 3
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'test'
|
||||
assert state.yaw_frame_id == 'map'
|
||||
|
||||
# set_yaw should not change the main mode
|
||||
res = set_yaw(yaw=1, frame_id='test2')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_POSITION
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.x == 5
|
||||
assert state.y == 6
|
||||
assert state.z == 3
|
||||
assert state.yaw == 1
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'test'
|
||||
assert state.yaw_frame_id == 'test2'
|
||||
|
||||
# test set_velocity
|
||||
res = set_velocity(vx=1, frame_id='body')
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_VELOCITY
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.vx == 1
|
||||
assert state.vy == 0
|
||||
assert state.vz == 0
|
||||
assert state.yaw == 0
|
||||
assert state.xy_frame_id == 'map'
|
||||
assert state.z_frame_id == 'map'
|
||||
assert state.yaw_frame_id == 'map'
|
||||
|
||||
# set_altitude should not work in velocity mode
|
||||
res = set_altitude(z=3, frame_id='test')
|
||||
assert res.success == False
|
||||
assert res.message.startswith('Altitude cannot be set in')
|
||||
|
||||
# test set_attitude
|
||||
res = set_attitude(roll=0.1, pitch=0.2, yaw=0.3, thrust=0.5)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_ATTITUDE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.roll == approx(0.1)
|
||||
assert state.pitch == approx(0.2)
|
||||
assert state.yaw == approx(0.3)
|
||||
assert state.thrust == approx(0.5)
|
||||
assert state.yaw_frame_id == 'map'
|
||||
msg = rospy.wait_for_message('/mavros/setpoint_attitude/attitude', PoseStamped, timeout=3)
|
||||
# Tait-Bryan ZYX angle (rzyx) converted to quaternion
|
||||
assert msg.pose.orientation.x == approx(0.0342708)
|
||||
assert msg.pose.orientation.y == approx(0.10602051)
|
||||
assert msg.pose.orientation.z == approx(0.14357218)
|
||||
assert msg.pose.orientation.w == approx(0.98334744)
|
||||
msg = rospy.wait_for_message('/mavros/setpoint_attitude/thrust', mavros_msgs.msg.Thrust, timeout=3)
|
||||
assert msg.thrust == approx(0.5)
|
||||
|
||||
# set_yaw should work in attitude mode
|
||||
res = set_yaw(yaw=0.7, frame_id='test2')
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_ATTITUDE
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW
|
||||
assert state.roll == approx(0.1)
|
||||
assert state.pitch == approx(0.2)
|
||||
assert state.yaw == approx(0.7)
|
||||
assert state.thrust == approx(0.5)
|
||||
assert state.yaw_frame_id == 'test2'
|
||||
|
||||
# set_yaw_rate should not work in attitude mode
|
||||
res = set_yaw_rate(yaw_rate=0.3)
|
||||
assert res.success == False
|
||||
assert res.message.startswith('Yaw rate cannot be set in')
|
||||
|
||||
# test set_rates
|
||||
res = set_rates(roll_rate=nan, pitch_rate=nan, yaw_rate=0.3, thrust=0.6)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_RATES
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
|
||||
assert state.roll_rate == approx(0)
|
||||
assert state.pitch_rate == approx(0)
|
||||
assert state.yaw_rate == approx(0.3)
|
||||
assert state.thrust == approx(0.6)
|
||||
msg = rospy.wait_for_message('/mavros/setpoint_raw/attitude', mavros_msgs.msg.AttitudeTarget, timeout=3)
|
||||
assert msg.thrust == approx(0.6)
|
||||
|
||||
res = set_rates(roll_rate=0.3, pitch_rate=0.2, yaw_rate=0.1, thrust=0.4)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_RATES
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
|
||||
assert state.roll_rate == approx(0.3)
|
||||
assert state.pitch_rate == approx(0.2)
|
||||
assert state.yaw_rate == approx(0.1)
|
||||
assert state.thrust == approx(0.4)
|
||||
|
||||
res = set_rates(roll_rate=nan, pitch_rate=nan, yaw_rate=nan, thrust=0.3)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_RATES
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
|
||||
assert state.roll_rate == approx(0.3)
|
||||
assert state.pitch_rate == approx(0.2)
|
||||
assert state.yaw_rate == approx(0.1)
|
||||
assert state.thrust == approx(0.3)
|
||||
msg = rospy.wait_for_message('/mavros/setpoint_raw/attitude', mavros_msgs.msg.AttitudeTarget, timeout=3)
|
||||
assert msg.type_mask == mavros_msgs.msg.AttitudeTarget.IGNORE_ATTITUDE
|
||||
assert msg.body_rate.x == approx(0.3)
|
||||
assert msg.body_rate.y == approx(0.2)
|
||||
assert msg.body_rate.z == approx(0.1)
|
||||
|
||||
# set_yaw_rate should work in rates mode
|
||||
res = set_yaw_rate(yaw_rate=0.4)
|
||||
assert res.success == True
|
||||
state = get_state()
|
||||
assert state.mode == State.MODE_RATES
|
||||
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
|
||||
assert state.roll_rate == approx(0.3)
|
||||
assert state.pitch_rate == approx(0.2)
|
||||
assert state.yaw_rate == approx(0.4)
|
||||
assert state.thrust == approx(0.3)
|
||||
|
||||
res = set_rates(roll_rate=inf)
|
||||
assert res.success == False
|
||||
assert res.message == 'roll_rate argument cannot be Inf'
|
||||
@@ -1,10 +0,0 @@
|
||||
<launch>
|
||||
<node name="simple_offboard" pkg="clover" type="simple_offboard" required="true" output="screen"/>
|
||||
|
||||
<node pkg="tf2_ros" type="static_transform_publisher" name="test_frame" args="10 20 30 0 0 0 map test"/>
|
||||
|
||||
<node pkg="tf2_ros" type="static_transform_publisher" name="test2_frame" args="100 200 300 0 0 0 map test2"/>
|
||||
|
||||
<param name="test_module" value="$(find clover)/test/offboard.py"/>
|
||||
<test test-name="offboard_test" pkg="ros_pytest" type="ros_pytest_runner"/>
|
||||
</launch>
|
||||
@@ -15,7 +15,6 @@ const COLOR_GPIO = 200;
|
||||
const DOCS_URL = 'https://clover.coex.tech/en/blocks.html';
|
||||
|
||||
var frameIds = [["body", "BODY"], ["markers map", "ARUCO_MAP"], ["marker", "ARUCO"], ["last navigate target", "NAVIGATE_TARGET"], ["map", "MAP"]];
|
||||
var frameIdsWithTerrain = frameIds.concat([["terrain", "TERRAIN"]]);
|
||||
|
||||
function considerFrameId(e) {
|
||||
if (!(e instanceof Blockly.Events.Change || e instanceof Blockly.Events.Create)) return;
|
||||
@@ -23,7 +22,7 @@ function considerFrameId(e) {
|
||||
var frameId = this.getFieldValue('FRAME_ID');
|
||||
// set appropriate coordinates labels
|
||||
if (this.getInput('X')) { // block has x-y-z fields
|
||||
if (frameId == 'BODY' || frameId == 'NAVIGATE_TARGET' || frameId == 'BASE_LINK' || frameId == 'TERRAIN') {
|
||||
if (frameId == 'BODY' || frameId == 'NAVIGATE_TARGET' || frameId == 'BASE_LINK') {
|
||||
this.getInput('X').fieldRow[0].setValue('forward');
|
||||
this.getInput('Y').fieldRow[0].setValue('left');
|
||||
this.getInput('Z').fieldRow[0].setValue('up');
|
||||
@@ -60,8 +59,8 @@ function updateSetpointBlock(e) {
|
||||
this.getInput('VY').setVisible(velocity);
|
||||
this.getInput('VZ').setVisible(velocity);
|
||||
this.getInput('YAW').setVisible(attitude);
|
||||
this.getInput('ROLL').setVisible(attitude);
|
||||
this.getInput('PITCH').setVisible(attitude);
|
||||
this.getInput('ROLL').setVisible(attitude);
|
||||
this.getInput('THRUST').setVisible(attitude);
|
||||
this.getInput('RELATIVE_TO').setVisible(type != 'RATES');
|
||||
|
||||
@@ -74,7 +73,7 @@ function updateSetpointBlock(e) {
|
||||
|
||||
Blockly.Blocks['navigate'] = {
|
||||
init: function () {
|
||||
let navFrameId = frameIdsWithTerrain.slice();
|
||||
let navFrameId = frameIds.slice();
|
||||
navFrameId.push(['global', 'GLOBAL_LOCAL'])
|
||||
navFrameId.push(['global, WGS 84 alt.', 'GLOBAL'])
|
||||
this.appendDummyInput()
|
||||
@@ -164,14 +163,14 @@ Blockly.Blocks['setpoint'] = {
|
||||
this.appendValueInput("VZ")
|
||||
.setCheck("Number")
|
||||
.appendField("vz");
|
||||
this.appendValueInput("ROLL")
|
||||
.setCheck("Number")
|
||||
.appendField("roll")
|
||||
.setVisible(false);
|
||||
this.appendValueInput("PITCH")
|
||||
.setCheck("Number")
|
||||
.appendField("pitch")
|
||||
.setVisible(false);
|
||||
this.appendValueInput("ROLL")
|
||||
.setCheck("Number")
|
||||
.appendField("roll")
|
||||
.setVisible(false);
|
||||
this.appendValueInput("YAW")
|
||||
.setCheck("Number")
|
||||
.appendField("yaw")
|
||||
@@ -214,7 +213,7 @@ Blockly.Blocks['get_position'] = {
|
||||
.appendField("current")
|
||||
.appendField(new Blockly.FieldDropdown([["x", "X"], ["y", "Y"], ["z", "Z"], ["vx", "VX"], ["vy", "VY"], ["vz", "VZ"]]), "FIELD")
|
||||
.appendField("relative to")
|
||||
.appendField(new Blockly.FieldDropdown(frameIdsWithTerrain), "FRAME_ID");
|
||||
.appendField(new Blockly.FieldDropdown(frameIds), "FRAME_ID");
|
||||
this.appendValueInput("ID")
|
||||
.setCheck("Number")
|
||||
.appendField("with ID")
|
||||
@@ -248,7 +247,7 @@ Blockly.Blocks['get_attitude'] = {
|
||||
init: function () {
|
||||
this.appendDummyInput()
|
||||
.appendField("current")
|
||||
.appendField(new Blockly.FieldDropdown([["roll", "ROLL"], ["pitch", "PITCH"], ["roll rate", "ROLL_RATE"], ["pitch rate", "PITCH_RATE"], ["yaw rate", "YAW_RATE"]]), "FIELD");
|
||||
.appendField(new Blockly.FieldDropdown([["pitch", "PITCH"], ["roll", "ROLL"], ["pitch rate", "PITCH_RATE"], ["roll rate", "ROLL_RATE"], ["yaw rate", "YAW_RATE"]]), "FIELD");
|
||||
this.setOutput(true, "Number");
|
||||
this.setColour(COLOR_STATE);
|
||||
this.setTooltip("Returns current orientation or angle rates in degree or degree per second (not radian).");
|
||||
@@ -510,7 +509,7 @@ Blockly.Blocks['distance'] = {
|
||||
.appendField("z");
|
||||
this.appendDummyInput()
|
||||
.appendField("relative to")
|
||||
.appendField(new Blockly.FieldDropdown([["markers map", "ARUCO_MAP"], ["marker", "ARUCO"], ["last navigate target", "NAVIGATE_TARGET"], ["terrain", "TERRAIN"]]), "FRAME_ID");
|
||||
.appendField(new Blockly.FieldDropdown([["markers map", "ARUCO_MAP"], ["marker", "ARUCO"], ["last navigate target", "NAVIGATE_TARGET"]]), "FRAME_ID");
|
||||
this.appendValueInput("ID")
|
||||
.setCheck("Number")
|
||||
.appendField("with ID")
|
||||
|
||||
@@ -69,8 +69,8 @@
|
||||
<value name="VX"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||
<value name="VY"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||
<value name="VZ"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||
<value name="ROLL"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||
<value name="PITCH"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||
<value name="ROLL"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||
<value name="YAW"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||
<value name="THRUST"><shadow type="math_number"><field name="NUM">0.5</field></shadow></value>
|
||||
<value name="ID"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||
|
||||
@@ -81,7 +81,7 @@ function generateROSDefinitions() {
|
||||
code += `get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)\n`;
|
||||
code += `navigate = rospy.ServiceProxy('navigate', srv.Navigate)\n`;
|
||||
if (rosDefinitions.navigateGlobal) {
|
||||
code += `navigate_global = rospy.ServiceProxy('navigate_global', srv.NavigateGlobal)\n`;
|
||||
code += `navigate_global = rospy.ServiceProxy('navigate_global', srv.NavigateGlobal)\n`;
|
||||
}
|
||||
if (rosDefinitions.setVelocity) {
|
||||
code += `set_velocity = rospy.ServiceProxy('set_velocity', srv.SetVelocity)\n`;
|
||||
@@ -276,11 +276,10 @@ Blockly.Python.angle = function(block) {
|
||||
}
|
||||
|
||||
Blockly.Python.set_yaw = function(block) {
|
||||
rosDefinitions.setYaw = true;
|
||||
simpleOffboard();
|
||||
let yaw = Blockly.Python.valueToCode(block, 'YAW', Blockly.Python.ORDER_NONE);
|
||||
let frameId = buildFrameId(block);
|
||||
let code = `set_yaw(yaw=${yaw}, frame_id=${frameId})\n`;
|
||||
let code = `navigate(x=float('nan'), y=float('nan'), z=float('nan'), yaw=${yaw}, frame_id=${frameId})\n`;
|
||||
if (block.getFieldValue('WAIT') == 'TRUE') {
|
||||
rosDefinitions.waitYaw = true;
|
||||
simpleOffboard();
|
||||
@@ -329,11 +328,11 @@ Blockly.Python.setpoint = function(block) {
|
||||
} else if (type == 'ATTITUDE') {
|
||||
rosDefinitions.setAttitude = true;
|
||||
simpleOffboard();
|
||||
return `set_attitude(roll=${roll}, pitch=${pitch}, yaw=${yaw}, thrust=${thrust}, frame_id=${frameId})\n`;
|
||||
return `set_attitude(pitch=${pitch}, roll=${roll}, yaw=${yaw}, thrust=${thrust}, frame_id=${frameId})\n`;
|
||||
} else if (type == 'RATES') {
|
||||
rosDefinitions.setRates = true;
|
||||
simpleOffboard();
|
||||
return `set_rates(roll_rate=${roll}, pitch_rate=${pitch}, yaw_rate=${yaw}, thrust=${thrust})\n`;
|
||||
return `set_rates(pitch_rate=${pitch}, roll_rate=${roll}, yaw_rate=${yaw}, thrust=${thrust})\n`;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -36,7 +36,7 @@
|
||||
* [Optical Flow](optical_flow.md)
|
||||
* [Autonomous flight (OFFBOARD)](simple_offboard.md)
|
||||
* [Coordinate systems (frames)](frames.md)
|
||||
* [Code examples](snippets.md)
|
||||
* [Code snippets](snippets.md)
|
||||
* [Interfacing with a laser rangefinder](laser.md)
|
||||
* [LED strip](leds.md)
|
||||
* [Working with GPIO](gpio.md)
|
||||
|
||||
@@ -14,7 +14,7 @@ The `clover` service must be restarted after the launch-file has been edited:
|
||||
sudo systemctl restart clover
|
||||
```
|
||||
|
||||
You may use [rqt](rviz.md) or [web_video_server](web_video_server.md) to view the camera stream.
|
||||
You may use rqt or [web_video_server](web_video_server.md) to view the camera stream.
|
||||
|
||||
## Troubleshooting
|
||||
|
||||
@@ -52,6 +52,8 @@ The [SD card image](image.md) comes with a preinstalled [OpenCV](https://opencv.
|
||||
|
||||
### Python
|
||||
|
||||
Main article: http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython.
|
||||
|
||||
An example of creating a subscriber for a topic with an image from the main camera for processing with OpenCV:
|
||||
|
||||
```python
|
||||
@@ -59,14 +61,12 @@ import rospy
|
||||
import cv2
|
||||
from sensor_msgs.msg import Image
|
||||
from cv_bridge import CvBridge
|
||||
from clover import long_callback
|
||||
|
||||
rospy.init_node('cv')
|
||||
rospy.init_node('computer_vision_sample')
|
||||
bridge = CvBridge()
|
||||
|
||||
@long_callback
|
||||
def image_callback(data):
|
||||
img = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
|
||||
cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
|
||||
# Do any image processing with cv2...
|
||||
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
|
||||
@@ -74,31 +74,19 @@ image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
|
||||
rospy.spin()
|
||||
```
|
||||
|
||||
> **Note** Image processing may take significant time to finish. This can cause an [issue](https://github.com/ros/ros_comm/issues/1901) in rospy library, which would lead to processing stale camera frames. To solve this problem you need to use `long_callback` decorator from `clover` library, as in the example above.
|
||||
|
||||
#### Limiting CPU usage
|
||||
|
||||
When using the `main_camera/image_raw` topic, the script will process the maximum number of frames from the camera, actively utilizing the CPU (up to 100%). In tasks, where processing each camera frame is not critical, you can use the topic, where the frames are published at rate 5 Hz: `main_camera/image_raw_throttled`:
|
||||
|
||||
```python
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1)
|
||||
```
|
||||
|
||||
#### Publishing images
|
||||
|
||||
To debug image processing, you can publish a separate topic with the processed image:
|
||||
|
||||
```python
|
||||
image_pub = rospy.Publisher('~debug', Image)
|
||||
```
|
||||
|
||||
Publishing the processed image:
|
||||
Publishing the processed image (at the end of the image_callback function):
|
||||
|
||||
```python
|
||||
image_pub.publish(bridge.cv2_to_imgmsg(img, 'bgr8'))
|
||||
image_pub.publish(bridge.cv2_to_imgmsg(cv_image, 'bgr8'))
|
||||
```
|
||||
|
||||
The published images can be viewed using [web_video_server](web_video_server.md) or [rqt](rviz.md).
|
||||
The obtained images can be viewed using [web_video_server](web_video_server.md).
|
||||
|
||||
#### Retrieving one frame
|
||||
|
||||
@@ -109,7 +97,7 @@ import rospy
|
||||
from sensor_msgs.msg import Image
|
||||
from cv_bridge import CvBridge
|
||||
|
||||
rospy.init_node('cv')
|
||||
rospy.init_node('computer_vision_sample')
|
||||
bridge = CvBridge()
|
||||
|
||||
# ...
|
||||
@@ -131,32 +119,40 @@ QR codes recognition in Python:
|
||||
```python
|
||||
import rospy
|
||||
from pyzbar import pyzbar
|
||||
import cv2
|
||||
from cv_bridge import CvBridge
|
||||
from sensor_msgs.msg import Image
|
||||
from clover import long_callback
|
||||
|
||||
rospy.init_node('cv')
|
||||
bridge = CvBridge()
|
||||
|
||||
@long_callback
|
||||
def image_callback(msg):
|
||||
img = bridge.imgmsg_to_cv2(msg, 'bgr8')
|
||||
barcodes = pyzbar.decode(img)
|
||||
rospy.init_node('barcode_test')
|
||||
|
||||
# Image subscriber callback function
|
||||
def image_callback(data):
|
||||
cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
|
||||
barcodes = pyzbar.decode(cv_image)
|
||||
for barcode in barcodes:
|
||||
b_data = barcode.data.decode('utf-8')
|
||||
b_data = barcode.data.decode("utf-8")
|
||||
b_type = barcode.type
|
||||
(x, y, w, h) = barcode.rect
|
||||
xc = x + w/2
|
||||
yc = y + h/2
|
||||
print('Found {} with data {} with center at x={}, y={}'.format(b_type, b_data, xc, yc))
|
||||
print("Found {} with data {} with center at x={}, y={}".format(b_type, b_data, xc, yc))
|
||||
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1)
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
|
||||
|
||||
rospy.spin()
|
||||
```
|
||||
|
||||
> **Hint** See other computer vision examples in the `~/examples` directory of the [RPi image](image.md).
|
||||
The script will take up to 100% CPU capacity. To slow down the script artificially, you can use [throttling](http://wiki.ros.org/topic_tools/throttle) of frames from the camera, for example, at 5 Hz (`main_camera.launch`):
|
||||
|
||||
> **Note** Starting from [image](image.md) version **0.24** `image_raw_throttled` topic is available without addition configuration.
|
||||
|
||||
```xml
|
||||
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
||||
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
||||
```
|
||||
|
||||
The topic for the subscriber in this case should be changed for `main_camera/image_raw_throttled`.
|
||||
|
||||
## Video recording
|
||||
|
||||
|
||||
@@ -8,28 +8,6 @@ To learn more about the articles of the CopterHack finalist teams follow the lin
|
||||
|
||||
The proposed projects are supposed to be open-source and be compatible with the Clover quadcopter platform. Teams-participants are supposed to work on their projects throughout the competition, bringing them closer to the state of the finished product while being assisted by industry experts through lectures and regular feedback.
|
||||
|
||||
## Projects of the contest's participants {#participants}
|
||||
|
||||
|Place|Team|Project|Points|
|
||||
|:-:|-|-|-|
|
||||
||🇷🇺 Clover Cloud Team|[Clover Cloud Platform](https://github.com/DevMBS/clover/blob/clover-cloud-platform/docs/en/clover-cloud-platform.md)||
|
||||
||🇰🇬 Zavarka|[Система обмена грузами с помощью конвейера](https://github.com/aiurobotics/clover/blob/conveyance/docs/ru/conveyance.md)||
|
||||
||🇮🇳 DJS PHOENIX|[Autonomous Racing Drone](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix_chetak/docs/ru/djs_phoenix_chetak.md)||
|
||||
||🇷🇺 FSOTM|[Drone Interceptor](https://github.com/deadln/clover/blob/interceptor/docs/ru/interceptor.md)||
|
||||
||🇰🇬 Homelesses|[Trash Collector](https://github.com/Isa-jesus/clover/blob/trash-collector/docs/ru/trash-collector.md)||
|
||||
||🇷🇺 Digital otters|[Digital otters](https://github.com/Mentalsupernova/clover_cool/blob/new-article.md/docs/ru/new-article.md)||
|
||||
||🇷🇺 Light Flight|[Сопровождение БПЛА при посадке](https://github.com/SirSerow/clover_inertial_ns/blob/inertial-1/Description.md)||
|
||||
||🇰🇬 LiveSavers|[LiveSavers](https://github.com/Sarvar00/clover/blob/livesavers/docs/ru/livesaver.md)||
|
||||
||🇷🇺 C305|[Система радио-навигации](https://github.com/Lukerrr/clover-c305/blob/nav_beacon/docs/ru/nav-beacon.md)||
|
||||
||🇷🇺 XenCOM|[Bound by fate](https://github.com/xenkek/clover/blob/xenkek-patch-1/docs/ru/bound_by_fate.md)||
|
||||
||🇨🇦 Clover with Motion Capture System|[Clover with Motion Capture System](https://github.com/ssmith-81/clover/blob/MoCap_Clover/docs/en/mocap_clover.md)||
|
||||
||🇧🇷 Atena|[Swarm in Blocks 2](https://github.com/Grupo-SEMEAR-USP/clover/blob/swarm_in_blocks_2/docs/en/swarm_in_blocks_2.md)||
|
||||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover3/docs/ru/advanced_clover_simulator_platform.md)||
|
||||
||🇷🇺 Лицей №128|[Платформа для зарядки квадрокоптера](https://github.com/Juli-Shvetsova/clover/blob/liceu128-1/docs/ru/liceu128.md)||
|
||||
||🇷🇺 Ava_Clover|[DoubleClover](https://github.com/bessiaka/clover/blob/Ava_Clover/docs/ru/soosocta.md)||
|
||||
||🇷🇺 TPU_1|[Совместная транспортировка груза](https://github.com/shamoleg/clover/blob/tpu_1/docs/ru/tpu_1.md)||
|
||||
||🇷🇺 TPU_2|[Алгоритм полета сквозь лесную местность](https://github.com/shamoleg/clover/blob/tpu_2/docs/ru/tpu_2.md)| |
|
||||
|
||||
## CopterHack 2023 stages
|
||||
|
||||
The qualifying and project development stages will be held in an online format, however, the final round will be in a hybrid mode (offline + online). The competition involves monthly updates from the teams with regular feedback from the jury. All teams are required to prepare a final video and presentation on the project's results to participate in the final stage.
|
||||
|
||||
@@ -60,8 +60,8 @@ The `SYS_MC_EST_GROUP` parameter defines the estimator subsystem to use.
|
||||
|
||||
Estimator subsystem is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes:
|
||||
|
||||
* Angle rate of the copter – roll_rate, pitch_rate, yaw_rate;
|
||||
* Copter orientation (in the local coordinate system) – roll, pitch, yaw (one of presentations);
|
||||
* Angle rate of the copter – pitch_rate, roll_rate, yaw_rate;
|
||||
* Copter orientation (in the local coordinate system) – pitch, roll, yaw (one of presentations);
|
||||
* Copter position (in the local coordinate system) – x, y, z;
|
||||
* Copter speed (in the local coordinate system) – vx, vy, vz;
|
||||
* Global coordinates of the copter – latitude, longitude, altitude;
|
||||
|
||||
@@ -51,11 +51,11 @@ Response format:
|
||||
* `lat, lon` – drone latitude and longitude *(degrees)*, requires [GPS](gps.md) module;
|
||||
* `alt` – altitude in the global coordinate system (according to [WGS-84](https://ru.wikipedia.org/wiki/WGS_84) standard, not <abbr title="Above Mean Sea Level">AMSL</abbr>!), requires [GPS](gps.md) module;
|
||||
* `vx, vy, vz` – drone velocity *(m/s)*;
|
||||
* `roll` – roll angle *(radians)*;
|
||||
* `pitch` – pitch angle *(radians)*;
|
||||
* `roll` – roll angle *(radians)*;
|
||||
* `yaw` — yaw angle *(radians)*;
|
||||
* `roll_rate` – angular roll velocity *(rad/s)*;
|
||||
* `pitch_rate` — angular pitch velocity *(rad/s)*;
|
||||
* `roll_rate` – angular roll velocity *(rad/s)*;
|
||||
* `yaw_rate` – angular yaw velocity *(rad/s)*;
|
||||
* `voltage` – total battery voltage *(V)*;
|
||||
* `cell_voltage` – battery cell voltage *(V)*.
|
||||
@@ -261,22 +261,22 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
|
||||
|
||||
### set_attitude
|
||||
|
||||
Set roll, pitch, yaw and throttle level (similar to [the `STABILIZED` mode](modes.md)). This service may be used for lower level control of the drone behavior, or controlling the drone when no reliable data on its position is available.
|
||||
Set pitch, roll, yaw and throttle level (similar to [the `STABILIZED` mode](modes.md)). This service may be used for lower level control of the drone behavior, or controlling the drone when no reliable data on its position is available.
|
||||
|
||||
Parameters:
|
||||
|
||||
* `roll`, `pitch`, `yaw` – requested roll, pitch, and yaw angle *(radians)*;
|
||||
* `pitch`, `roll`, `yaw` – requested pitch, roll, and yaw angle *(radians)*;
|
||||
* `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
|
||||
* `auto_arm` – switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
|
||||
* `frame_id` – [coordinate system](frames.md) for `yaw` (Default value: `map`).
|
||||
|
||||
### set_rates
|
||||
|
||||
Set roll, pitch, and yaw rates and the throttle level (similar to [the `ACRO` mode](modes.md)). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform aerobatic tricks (e.g., flips).
|
||||
Set pitch, roll, and yaw rates and the throttle level (similar to [the `ACRO` mode](modes.md)). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform aerobatic tricks (e.g., flips).
|
||||
|
||||
Parameters:
|
||||
|
||||
* `roll_rate`, `pitch_rate`, `yaw_rate` – pitch, roll, and yaw rates *(rad/s)*;
|
||||
* `pitch_rate`, `roll_rate`, `yaw_rate` – pitch, roll, and yaw rates *(rad/s)*;
|
||||
* `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
|
||||
* `auto_arm` – switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
|
||||
|
||||
|
||||
@@ -144,7 +144,7 @@ Determine whether the copter is turned upside-down:
|
||||
PI_2 = math.pi / 2
|
||||
telem = get_telemetry()
|
||||
|
||||
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2
|
||||
flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
|
||||
```
|
||||
|
||||
### # {#angle-hor}
|
||||
@@ -155,8 +155,8 @@ Calculate the copter horizontal angle:
|
||||
PI_2 = math.pi / 2
|
||||
telem = get_telemetry()
|
||||
|
||||
flipped = not -PI_2 <= telem.roll <= PI_2 or not -PI_2 <= telem.pitch <= PI_2
|
||||
angle_to_horizon = math.atan(math.hypot(math.tan(telem.roll), math.tan(telem.pitch)))
|
||||
flipped = not -PI_2 <= telem.pitch <= PI_2 or not -PI_2 <= telem.roll <= PI_2
|
||||
angle_to_horizon = math.atan(math.hypot(math.tan(telem.pitch), math.tan(telem.roll)))
|
||||
if flipped:
|
||||
angle_to_horizon = math.pi - angle_to_horizon
|
||||
```
|
||||
@@ -324,7 +324,7 @@ def flip():
|
||||
|
||||
while True:
|
||||
telem = get_telemetry()
|
||||
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2
|
||||
flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
|
||||
if flipped:
|
||||
break
|
||||
|
||||
|
||||
@@ -54,6 +54,8 @@ raspistill -o test.jpg
|
||||
|
||||
### Python
|
||||
|
||||
Основная статья: http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython.
|
||||
|
||||
Пример создания подписчика на топик с изображением с основной камеры для обработки с использованием OpenCV:
|
||||
|
||||
```python
|
||||
@@ -61,14 +63,12 @@ import rospy
|
||||
import cv2
|
||||
from sensor_msgs.msg import Image
|
||||
from cv_bridge import CvBridge
|
||||
from clover import long_callback
|
||||
|
||||
rospy.init_node('cv')
|
||||
rospy.init_node('computer_vision_sample')
|
||||
bridge = CvBridge()
|
||||
|
||||
@long_callback
|
||||
def image_callback(data):
|
||||
img = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
|
||||
cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
|
||||
# Do any image processing with cv2...
|
||||
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
|
||||
@@ -76,31 +76,19 @@ image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
|
||||
rospy.spin()
|
||||
```
|
||||
|
||||
> **Note** Обработка изображения может занимать значительное время. Это может вызвать [проблему](https://github.com/ros/ros_comm/issues/1901) в библиотеке rospy, которая приведет к обработке устаревших кадров с камеры. Для решения этой проблемы необходимо использовать декоратор `long_callback` из библиотеки `clover`, как в примере выше.
|
||||
|
||||
#### Ограничение использования CPU
|
||||
|
||||
При использовании топика `main_camera/image_raw` скрипт будет обрабатывать максимальное количество кадров с камеры, активно используя CPU (вплоть до 100%). В задачах, где обработка каждого кадра не критична, можно использовать топик, где кадры публикуются с частотой 5 Гц: `main_camera/image_raw_throttled`:
|
||||
|
||||
```python
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1)
|
||||
```
|
||||
|
||||
#### Публикация изображений
|
||||
|
||||
Для отладки обработки изображения можно публиковать отдельный топик с обработанным изображением:
|
||||
|
||||
```python
|
||||
image_pub = rospy.Publisher('~debug', Image)
|
||||
```
|
||||
|
||||
Публикация обработанного изображения:
|
||||
Публикация обработанного изображения (в конце функции image_callback):
|
||||
|
||||
```python
|
||||
image_pub.publish(bridge.cv2_to_imgmsg(img, 'bgr8'))
|
||||
image_pub.publish(bridge.cv2_to_imgmsg(cv_image, 'bgr8'))
|
||||
```
|
||||
|
||||
Получаемые изображения можно просматривать используя [web_video_server](web_video_server.md) или [rqt](rviz.md).
|
||||
Получаемые изображения можно просматривать используя [web_video_server](web_video_server.md).
|
||||
|
||||
#### Получение одного кадра
|
||||
|
||||
@@ -111,12 +99,12 @@ import rospy
|
||||
from sensor_msgs.msg import Image
|
||||
from cv_bridge import CvBridge
|
||||
|
||||
rospy.init_node('cv')
|
||||
rospy.init_node('computer_vision_sample')
|
||||
bridge = CvBridge()
|
||||
|
||||
# ...
|
||||
|
||||
# Retrieve a frame:
|
||||
# Получение кадра:
|
||||
img = bridge.imgmsg_to_cv2(rospy.wait_for_message('main_camera/image_raw', Image), 'bgr8')
|
||||
```
|
||||
|
||||
@@ -133,32 +121,40 @@ img = bridge.imgmsg_to_cv2(rospy.wait_for_message('main_camera/image_raw', Image
|
||||
```python
|
||||
import rospy
|
||||
from pyzbar import pyzbar
|
||||
import cv2
|
||||
from cv_bridge import CvBridge
|
||||
from sensor_msgs.msg import Image
|
||||
from clover import long_callback
|
||||
|
||||
rospy.init_node('cv')
|
||||
bridge = CvBridge()
|
||||
|
||||
@long_callback
|
||||
def image_callback(msg):
|
||||
img = bridge.imgmsg_to_cv2(msg, 'bgr8')
|
||||
barcodes = pyzbar.decode(img)
|
||||
rospy.init_node('barcode_test')
|
||||
|
||||
# Image subscriber callback function
|
||||
def image_callback(data):
|
||||
cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
|
||||
barcodes = pyzbar.decode(cv_image)
|
||||
for barcode in barcodes:
|
||||
b_data = barcode.data.decode('utf-8')
|
||||
b_data = barcode.data.decode("utf-8")
|
||||
b_type = barcode.type
|
||||
(x, y, w, h) = barcode.rect
|
||||
xc = x + w/2
|
||||
yc = y + h/2
|
||||
print('Found {} with data {} with center at x={}, y={}'.format(b_type, b_data, xc, yc))
|
||||
print("Found {} with data {} with center at x={}, y={}".format(b_type, b_data, xc, yc))
|
||||
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1)
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
|
||||
|
||||
rospy.spin()
|
||||
```
|
||||
|
||||
> **Hint** Смотрите другие примеры по работе с компьютерным зрением в каталоге `~/examples` [образа для RPi](image.md).
|
||||
Скрипт будет занимать 100% процессора. Для искусственного замедления работы скрипта можно запустить [throttling](http://wiki.ros.org/topic_tools/throttle) кадров с камеры, например, в 5 Гц (`main_camera.launch`):
|
||||
|
||||
> **Note** Начиная с версии [образа](image.md) **0.24** топик `image_raw_throttled` доступен без дополнительной конфигурации.
|
||||
|
||||
```xml
|
||||
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
||||
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
||||
```
|
||||
|
||||
Топик для подписчика в этом случае необходимо поменять на `main_camera/image_raw_throttled`.
|
||||
|
||||
## Запись видео
|
||||
|
||||
|
||||
@@ -8,28 +8,6 @@ CopterHack 2023 — это международный конкурс по ра
|
||||
|
||||
На конкурс принимаются проекты с открытым исходным кодом и совместимые с платформой квадрокоптера "Клевер". На протяжении конкурса команды работают на собственными идеями и разработками, приближая их к состоянию готового продукта. В этом участникам помогают эксперты отрасли через лекции и регулярную обратную связь.
|
||||
|
||||
## Проекты участников конкурса {#participants}
|
||||
|
||||
|Место|Команда|Проект|Балл|
|
||||
|:-:|-|-|-|
|
||||
||🇷🇺 Clover Cloud Team|[Clover Cloud Platform](https://github.com/DevMBS/clover/blob/clover-cloud-platform/docs/en/clover-cloud-platform.md)||
|
||||
||🇰🇬 Zavarka|[Система обмена грузами с помощью конвейера](https://github.com/aiurobotics/clover/blob/conveyance/docs/ru/conveyance.md)||
|
||||
||🇮🇳 DJS PHOENIX|[Autonomous Racing Drone](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix_chetak/docs/ru/djs_phoenix_chetak.md)||
|
||||
||🇷🇺 FSOTM|[Дрон-перехватчик](https://github.com/deadln/clover/blob/interceptor/docs/ru/interceptor.md)||
|
||||
||🇰🇬 Бездомные|[Дрон-бездомный](https://github.com/Isa-jesus/clover/blob/trash-collector/docs/ru/trash-collector.md)||
|
||||
||🇷🇺 Digital otters|[Digital otters](https://github.com/Mentalsupernova/clover_cool/blob/new-article.md/docs/ru/new-article.md)||
|
||||
||🇷🇺 Light Flight|[Сопровождение БПЛА при посадке](https://github.com/SirSerow/clover_inertial_ns/blob/inertial-1/Description.md)||
|
||||
||🇰🇬 LiveSavers|[LiveSavers](https://github.com/Sarvar00/clover/blob/livesavers/docs/ru/livesaver.md)||
|
||||
||🇷🇺 C305|[Система радио-навигации](https://github.com/Lukerrr/clover-c305/blob/nav_beacon/docs/ru/nav-beacon.md)||
|
||||
||🇷🇺 XenCOM|[Bound by fate](https://github.com/xenkek/clover/blob/xenkek-patch-1/docs/ru/bound_by_fate.md)||
|
||||
||🇨🇦 Clover with Motion Capture System|[Clover with Motion Capture System](https://github.com/ssmith-81/clover/blob/MoCap_Clover/docs/en/mocap_clover.md)||
|
||||
||🇧🇷 Atena|[Swarm in Blocks 2](https://github.com/Grupo-SEMEAR-USP/clover/blob/swarm_in_blocks_2/docs/en/swarm_in_blocks_2.md)||
|
||||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover3/docs/ru/advanced_clover_simulator_platform.md)||
|
||||
||🇷🇺 Лицей №128|[Платформа для зарядки квадрокоптера](https://github.com/Juli-Shvetsova/clover/blob/liceu128-1/docs/ru/liceu128.md)||
|
||||
||🇷🇺 Ava_Clover|[DoubleClover](https://github.com/bessiaka/clover/blob/Ava_Clover/docs/ru/soosocta.md)||
|
||||
||🇷🇺 TPU_1|[Совместная транспортировка груза](https://github.com/shamoleg/clover/blob/tpu_1/docs/ru/tpu_1.md)||
|
||||
||🇷🇺 TPU_2|[Алгоритм полета сквозь лесную местность](https://github.com/shamoleg/clover/blob/tpu_2/docs/ru/tpu_2.md)| |
|
||||
|
||||
## Этапы CopterHack 2023
|
||||
|
||||
Отборочный и проектный этапы конкурса проходят в онлайн-формате, формат проведения финала – гибридный (оффлайн + онлайн). Конкурс подразумевает ежемесячные апдейты от команд с получением регулярной обратной связи от жюри. Для участия в заключительном этапе необходимо подготовить финальное видео и презентацию о результатах проекта.
|
||||
|
||||
@@ -60,8 +60,8 @@
|
||||
|
||||
Estimator это подсистема, которая вычисляет текущее состояние (state) коптера, используя показания с датчиков. В состояние коптера входит:
|
||||
|
||||
* угловая скорость коптера – roll_rate, pitch_rate, yaw_rate;
|
||||
* ориентация коптера (в локальной системе координат) – roll (крен), pitch (тангаж), yaw (рысканье) (одно из представлений);
|
||||
* угловая скорость коптера – pitch_rate, roll_rate, yaw_rate;
|
||||
* ориентация коптера (в локальной системе координат) – pitch (тангаж), roll (крен), yaw (рысканье) (одно из представлений);
|
||||
* позиция коптера (в локальной системе координат) – x, y, z;
|
||||
* скорость коптера (в локальной системе координат) – vx, vy, vz;
|
||||
* глобальные координаты коптера – latitude, longitude, altitude;
|
||||
|
||||
@@ -51,11 +51,11 @@ land = rospy.ServiceProxy('land', Trigger)
|
||||
* `lat, lon` – широта, долгота *(градусы)*, необходимо наличие [GPS](gps.md);
|
||||
* `alt` – высота в глобальной системе координат (стандарт [WGS-84](https://ru.wikipedia.org/wiki/WGS_84), не <abbr title="Above Mean Sea Level, выше среднего уровня моря">AMSL</abbr>!), необходимо наличие [GPS](gps.md);
|
||||
* `vx, vy, vz` – скорость коптера *(м/с)*;
|
||||
* `roll` – угол по крену *(радианы)*;
|
||||
* `pitch` – угол по тангажу *(радианы)*;
|
||||
* `roll` – угол по крену *(радианы)*;
|
||||
* `yaw` – угол по рысканью *(радианы)*;
|
||||
* `roll_rate` – угловая скорость по крену *(рад/с)*;
|
||||
* `pitch_rate` – угловая скорость по тангажу *(рад/с)*;
|
||||
* `roll_rate` – угловая скорость по крену *(рад/с)*;
|
||||
* `yaw_rate` – угловая скорость по рысканью *(рад/с)*;
|
||||
* `voltage` – общее напряжение аккумулятора *(В)*;
|
||||
* `cell_voltage` – напряжение аккумулятора на ячейку *(В)*.
|
||||
@@ -265,7 +265,7 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
|
||||
|
||||
Параметры:
|
||||
|
||||
* `roll`, `pitch`, `yaw` – необходимый угол по тангажу, крену и рысканью *(радианы)*;
|
||||
* `pitch`, `roll`, `yaw` – необходимый угол по тангажу, крену и рысканью *(радианы)*;
|
||||
* `thrust` – уровень газа от 0 (нет газа, пропеллеры остановлены) до 1 (полный газ);
|
||||
* `auto_arm` – перевести коптер в `OFFBOARD` и заармить автоматически (**коптер взлетит**);
|
||||
* `frame_id` – [система координат](frames.md), в которой задан `yaw` (по умолчанию: `map`).
|
||||
@@ -276,7 +276,7 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
|
||||
|
||||
Параметры:
|
||||
|
||||
* `roll_rate`, `pitch_rate`, `yaw_rate` – угловая скорость по тангажу, крену и рыканью *(рад/с)*;
|
||||
* `pitch_rate`, `roll_rate`, `yaw_rate` – угловая скорость по тангажу, крену и рыканью *(рад/с)*;
|
||||
* `thrust` – уровень газа от 0 (нет газа, пропеллеры остановлены) до 1 (полный газ).
|
||||
* `auto_arm` – перевести коптер в `OFFBOARD` и заармить автоматически (**коптер взлетит**);
|
||||
|
||||
|
||||
@@ -154,7 +154,7 @@ new_pose = tf_buffer.transform(pose, frame_id, transform_timeout)
|
||||
PI_2 = math.pi / 2
|
||||
telem = get_telemetry()
|
||||
|
||||
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2
|
||||
flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
|
||||
```
|
||||
|
||||
### # {#angle-hor}
|
||||
@@ -165,7 +165,7 @@ flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2
|
||||
PI_2 = math.pi / 2
|
||||
telem = get_telemetry()
|
||||
|
||||
flipped = not -PI_2 <= telem.roll <= PI_2 or not -PI_2 <= telem.pitch <= PI_2
|
||||
flipped = not -PI_2 <= telem.pitch <= PI_2 or not -PI_2 <= telem.roll <= PI_2
|
||||
angle_to_horizon = math.atan(math.hypot(math.tan(telem.pitch), math.tan(telem.roll)))
|
||||
if flipped:
|
||||
angle_to_horizon = math.pi - angle_to_horizon
|
||||
@@ -335,7 +335,7 @@ def flip():
|
||||
|
||||
while True:
|
||||
telem = get_telemetry()
|
||||
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2
|
||||
flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
|
||||
if flipped:
|
||||
break
|
||||
|
||||
|
||||
Reference in New Issue
Block a user