mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-01 15:39:32 +00:00
Compare commits
23 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
e31d552c78 | ||
|
|
fe0a98e11c | ||
|
|
921e09c392 | ||
|
|
9e69bdb01b | ||
|
|
50495a9de9 | ||
|
|
12ccd919a2 | ||
|
|
f0eacfc0f7 | ||
|
|
742d0535c3 | ||
|
|
af1b993e64 | ||
|
|
d3bda9df48 | ||
|
|
939086362a | ||
|
|
7cf14373b0 | ||
|
|
f428dfdb50 | ||
|
|
76982dc198 | ||
|
|
29f01c25e0 | ||
|
|
7ca0ede1d7 | ||
|
|
c3d87b1608 | ||
|
|
47901dcff2 | ||
|
|
4b2147185f | ||
|
|
44da0e3e9f | ||
|
|
bdcfb7a734 | ||
|
|
9404d4be6d | ||
|
|
ad51d86464 |
6
.github/workflows/build-image.yaml
vendored
6
.github/workflows/build-image.yaml
vendored
@@ -27,3 +27,9 @@ jobs:
|
|||||||
prerelease: true
|
prerelease: true
|
||||||
env:
|
env:
|
||||||
GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }}
|
GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }}
|
||||||
|
- name: Upload image to artifacts
|
||||||
|
uses: actions/upload-artifact@v3
|
||||||
|
with:
|
||||||
|
name: image
|
||||||
|
path: images/clover_*.zip
|
||||||
|
retention-days: 1
|
||||||
|
|||||||
@@ -4,7 +4,10 @@ PACKAGE = "aruco_pose"
|
|||||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||||
import cv2.aruco
|
import cv2.aruco
|
||||||
|
|
||||||
p = cv2.aruco.DetectorParameters_create()
|
try:
|
||||||
|
p = cv2.aruco.DetectorParameters_create()
|
||||||
|
except AttributeError:
|
||||||
|
p = cv2.aruco.DetectorParameters()
|
||||||
|
|
||||||
gen = ParameterGenerator()
|
gen = ParameterGenerator()
|
||||||
|
|
||||||
|
|||||||
@@ -138,7 +138,9 @@ my_travis_retry apt-get install -y --no-install-recommends \
|
|||||||
ros-${ROS_DISTRO}-rosshow \
|
ros-${ROS_DISTRO}-rosshow \
|
||||||
ros-${ROS_DISTRO}-cmake-modules \
|
ros-${ROS_DISTRO}-cmake-modules \
|
||||||
ros-${ROS_DISTRO}-image-view \
|
ros-${ROS_DISTRO}-image-view \
|
||||||
ros-${ROS_DISTRO}-image-geometry
|
ros-${ROS_DISTRO}-image-geometry \
|
||||||
|
ros-${ROS_DISTRO}-nodelet-topic-tools \
|
||||||
|
ros-${ROS_DISTRO}-stereo-msgs
|
||||||
|
|
||||||
# TODO move GeographicLib datasets to Mavros debian package
|
# TODO move GeographicLib datasets to Mavros debian package
|
||||||
echo_stamp "Install GeographicLib datasets (needed for mavros)" \
|
echo_stamp "Install GeographicLib datasets (needed for mavros)" \
|
||||||
@@ -178,11 +180,14 @@ source /opt/ros/${ROS_DISTRO}/setup.bash
|
|||||||
source /home/pi/catkin_ws/devel/setup.bash
|
source /home/pi/catkin_ws/devel/setup.bash
|
||||||
EOF
|
EOF
|
||||||
|
|
||||||
|
echo "List of all downloaded deb-files"
|
||||||
|
ls /var/cache/apt/archives
|
||||||
|
|
||||||
#echo_stamp "Removing local apt mirror"
|
#echo_stamp "Removing local apt mirror"
|
||||||
# Restore original sources.list
|
# Restore original sources.list
|
||||||
#mv /var/sources.list.bak /etc/apt/sources.list
|
#mv /var/sources.list.bak /etc/apt/sources.list
|
||||||
# Clean apt cache
|
# Clean apt cache
|
||||||
apt-get clean -qq > /dev/null
|
#apt-get clean -qq > /dev/null
|
||||||
# Remove local mirror repository key
|
# Remove local mirror repository key
|
||||||
#apt-key del COEX-MIRROR
|
#apt-key del COEX-MIRROR
|
||||||
|
|
||||||
|
|||||||
@@ -18,7 +18,7 @@ EXCLUDE = 'rviz.png', 'ssid.png', 'sitl_docker_demo.png', 'qgc-params.png', 'but
|
|||||||
'qgc-battery.png', 'qgc-radio.png', 'qgc-cal-acc.png', 'qgc-esc.png', 'qgc-cal-compass.png', \
|
'qgc-battery.png', 'qgc-radio.png', 'qgc-cal-acc.png', 'qgc-esc.png', 'qgc-cal-compass.png', \
|
||||||
'qgc.png', 'qgc-parameters.png', 'clever4-front-white-large.png', 'qgc-modes.png', \
|
'qgc.png', 'qgc-parameters.png', 'clever4-front-white-large.png', 'qgc-modes.png', \
|
||||||
'qgc-requires-setup.png', 'clever4-front-white.png', 'clever4-kit-white.png', '26_1.png', 'battery_holder.stl', \
|
'qgc-requires-setup.png', 'clever4-front-white.png', 'clever4-kit-white.png', '26_1.png', 'battery_holder.stl', \
|
||||||
'camera_case.stl', 'camera_mount.stl'
|
'camera_case.stl', 'camera_mount.stl', 'grip_right.stl', 'grip_left.stl'
|
||||||
|
|
||||||
code = 0
|
code = 0
|
||||||
|
|
||||||
|
|||||||
@@ -17,6 +17,7 @@ from cv_bridge import CvBridge
|
|||||||
from clover import long_callback, srv
|
from clover import long_callback, srv
|
||||||
import tf2_ros
|
import tf2_ros
|
||||||
import tf2_geometry_msgs
|
import tf2_geometry_msgs
|
||||||
|
import image_geometry
|
||||||
|
|
||||||
rospy.init_node('cv', disable_signals=True) # disable signals to allow interrupting with ctrl+c
|
rospy.init_node('cv', disable_signals=True) # disable signals to allow interrupting with ctrl+c
|
||||||
|
|
||||||
@@ -32,21 +33,14 @@ mask_pub = rospy.Publisher('~mask', Image, queue_size=1)
|
|||||||
point_pub = rospy.Publisher('~red_circle', PointStamped, queue_size=1)
|
point_pub = rospy.Publisher('~red_circle', PointStamped, queue_size=1)
|
||||||
|
|
||||||
# read camera info
|
# read camera info
|
||||||
camera_info = rospy.wait_for_message('main_camera/camera_info', CameraInfo)
|
camera_model = image_geometry.PinholeCameraModel()
|
||||||
camera_matrix = np.float64(camera_info.K).reshape(3, 3)
|
camera_model.fromCameraInfo(rospy.wait_for_message('main_camera/camera_info', CameraInfo))
|
||||||
distortion = np.float64(camera_info.D).flatten()
|
|
||||||
|
|
||||||
|
|
||||||
def img_xy_to_point(xy, dist):
|
def img_xy_to_point(xy, dist):
|
||||||
xy = cv2.undistortPoints(xy, camera_matrix, distortion, P=camera_matrix)[0][0]
|
xy_rect = camera_model.rectifyPoint(xy)
|
||||||
|
ray = camera_model.projectPixelTo3dRay(xy_rect)
|
||||||
# Shift points to center
|
return Point(x=ray[0] * dist, y=ray[1] * dist, z=dist)
|
||||||
xy -= camera_info.width // 2, camera_info.height // 2
|
|
||||||
|
|
||||||
fx = camera_matrix[0, 0]
|
|
||||||
fy = camera_matrix[1, 1]
|
|
||||||
|
|
||||||
return Point(x=xy[0] * dist / fx, y=xy[1] * dist / fy, z=dist)
|
|
||||||
|
|
||||||
def get_center_of_mass(mask):
|
def get_center_of_mass(mask):
|
||||||
M = cv2.moments(mask)
|
M = cv2.moments(mask)
|
||||||
|
|||||||
@@ -21,7 +21,8 @@
|
|||||||
</node>
|
</node>
|
||||||
|
|
||||||
<!-- high level led effects control, events notification with leds -->
|
<!-- high level led effects control, events notification with leds -->
|
||||||
<node pkg="clover" name="led_effect" type="led" ns="led" clear_params="true" output="screen" if="$(arg led_effect)">
|
<node pkg="clover" name="led_effect" type="led" clear_params="true" output="screen" if="$(arg led_effect)">
|
||||||
|
<param name="led" value="led"/>
|
||||||
<param name="blink_rate" value="2"/>
|
<param name="blink_rate" value="2"/>
|
||||||
<param name="fade_period" value="0.5"/>
|
<param name="fade_period" value="0.5"/>
|
||||||
<param name="rainbow_period" value="5"/>
|
<param name="rainbow_period" value="5"/>
|
||||||
|
|||||||
@@ -6,6 +6,7 @@
|
|||||||
<arg name="device" default="/dev/video0"/> <!-- v4l2 device -->
|
<arg name="device" default="/dev/video0"/> <!-- v4l2 device -->
|
||||||
<arg name="throttled_topic" default="true"/> <!-- enable throttled image topic -->
|
<arg name="throttled_topic" default="true"/> <!-- enable throttled image topic -->
|
||||||
<arg name="throttled_topic_rate" default="5.0"/> <!-- throttled image topic rate -->
|
<arg name="throttled_topic_rate" default="5.0"/> <!-- throttled image topic rate -->
|
||||||
|
<arg name="rectify" default="false"/> <!-- enable rectification -->
|
||||||
<arg name="simulator" default="false"/>
|
<arg name="simulator" default="false"/>
|
||||||
|
|
||||||
<node if="$(eval direction_z == 'down' and direction_y == 'backward')" pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>
|
<node if="$(eval direction_z == 'down' and direction_y == 'backward')" pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>
|
||||||
@@ -49,4 +50,11 @@
|
|||||||
<!-- image topic throttled -->
|
<!-- image topic throttled -->
|
||||||
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
|
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
|
||||||
args="messages image_raw $(arg throttled_topic_rate) image_raw_throttled" if="$(arg throttled_topic)"/>
|
args="messages image_raw $(arg throttled_topic_rate) image_raw_throttled" if="$(arg throttled_topic)"/>
|
||||||
|
|
||||||
|
<!-- rectified image topic -->
|
||||||
|
<node pkg="nodelet" type="nodelet" name="rectify" args="load image_proc/rectify main_camera_nodelet_manager" if="$(arg rectify)">
|
||||||
|
<remap from="image_mono" to="main_camera/image_raw"/>
|
||||||
|
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||||
|
<remap from="image_rect" to="main_camera/image_rect"/>
|
||||||
|
</node>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -42,6 +42,7 @@
|
|||||||
<depend condition="$ROS_PYTHON_VERSION == 2">python-lxml</depend>
|
<depend condition="$ROS_PYTHON_VERSION == 2">python-lxml</depend>
|
||||||
<depend condition="$ROS_PYTHON_VERSION == 3">python3-lxml</depend>
|
<depend condition="$ROS_PYTHON_VERSION == 3">python3-lxml</depend>
|
||||||
<depend>dynamic_reconfigure</depend>
|
<depend>dynamic_reconfigure</depend>
|
||||||
|
<depend>image_proc</depend>
|
||||||
<exec_depend>python-pymavlink</exec_depend>
|
<exec_depend>python-pymavlink</exec_depend>
|
||||||
<test_depend>ros_pytest</test_depend>
|
<test_depend>ros_pytest</test_depend>
|
||||||
|
|
||||||
|
|||||||
@@ -309,15 +309,19 @@ int main(int argc, char **argv)
|
|||||||
nh_priv.param("notify/low_battery/threshold", low_battery_threshold, 3.7);
|
nh_priv.param("notify/low_battery/threshold", low_battery_threshold, 3.7);
|
||||||
nh_priv.param("notify/error/ignore", error_ignore, {});
|
nh_priv.param("notify/error/ignore", error_ignore, {});
|
||||||
|
|
||||||
ros::service::waitForService("set_leds"); // cannot work without set_leds service
|
std::string led; // led namespace
|
||||||
set_leds_srv = nh.serviceClient<led_msgs::SetLEDs>("set_leds", true);
|
nh_priv.param("led", led, std::string("led"));
|
||||||
|
if (!led.empty()) led += "/";
|
||||||
|
|
||||||
|
ros::service::waitForService(led + "set_leds"); // cannot work without set_leds service
|
||||||
|
set_leds_srv = nh.serviceClient<led_msgs::SetLEDs>(led + "set_leds", true);
|
||||||
|
|
||||||
// wait for leds count info
|
// wait for leds count info
|
||||||
handleState(*ros::topic::waitForMessage<led_msgs::LEDStateArray>("state", nh));
|
handleState(*ros::topic::waitForMessage<led_msgs::LEDStateArray>(led + "state", nh));
|
||||||
|
|
||||||
auto state_sub = nh.subscribe("state", 1, &handleState);
|
auto state_sub = nh.subscribe(led + "state", 1, &handleState);
|
||||||
|
|
||||||
auto set_effect = nh.advertiseService("set_effect", &setEffect);
|
auto set_effect = nh.advertiseService(led + "set_effect", &setEffect);
|
||||||
|
|
||||||
auto mavros_state_sub = nh.subscribe("mavros/state", 1, &handleMavrosState);
|
auto mavros_state_sub = nh.subscribe("mavros/state", 1, &handleMavrosState);
|
||||||
auto battery_sub = nh.subscribe("mavros/battery", 1, &handleBattery);
|
auto battery_sub = nh.subscribe("mavros/battery", 1, &handleBattery);
|
||||||
|
|||||||
@@ -107,7 +107,7 @@ def ff(value, precision=2):
|
|||||||
param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
|
param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
|
||||||
|
|
||||||
|
|
||||||
def get_param(name, default=None):
|
def get_param(name, default=None, strict=True):
|
||||||
try:
|
try:
|
||||||
res = param_get(param_id=name)
|
res = param_get(param_id=name)
|
||||||
except rospy.ServiceException as e:
|
except rospy.ServiceException as e:
|
||||||
@@ -115,7 +115,8 @@ def get_param(name, default=None):
|
|||||||
return None
|
return None
|
||||||
|
|
||||||
if not res.success:
|
if not res.success:
|
||||||
failure('unable to retrieve PX4 parameter %s', name)
|
if strict:
|
||||||
|
failure('unable to retrieve PX4 parameter %s', name)
|
||||||
return default
|
return default
|
||||||
else:
|
else:
|
||||||
if res.value.integer != 0:
|
if res.value.integer != 0:
|
||||||
@@ -263,7 +264,7 @@ def check_fcu():
|
|||||||
est = get_param('SYS_MC_EST_GROUP')
|
est = get_param('SYS_MC_EST_GROUP')
|
||||||
if est == 1:
|
if est == 1:
|
||||||
info('selected estimator: LPE')
|
info('selected estimator: LPE')
|
||||||
fuse = get_param('LPE_FUSION')
|
fuse = int(get_param('LPE_FUSION'))
|
||||||
if fuse & (1 << 4):
|
if fuse & (1 << 4):
|
||||||
info('LPE_FUSION: land detector fusion is enabled')
|
info('LPE_FUSION: land detector fusion is enabled')
|
||||||
else:
|
else:
|
||||||
@@ -316,7 +317,13 @@ def check_fcu():
|
|||||||
failure('cannot read time sync offset')
|
failure('cannot read time sync offset')
|
||||||
|
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
failure('no MAVROS state (check wiring)')
|
failure('no MAVROS state')
|
||||||
|
fcu_url = rospy.get_param('mavros/fcu_url', '?')
|
||||||
|
if fcu_url == '/dev/px4fmu':
|
||||||
|
if not os.path.exists('/lib/udev/rules.d/99-px4fmu.rules'):
|
||||||
|
info('udev rules are not installed, install udev rules or change usb_device to /dev/ttyACM0 in mavros.launch')
|
||||||
|
else:
|
||||||
|
info('udev did\'t recognize px4fmu device, check wiring or change usb_device to /dev/ttyACM0 in mavros.launch')
|
||||||
info('fcu_url = %s', rospy.get_param('mavros/fcu_url', '?'))
|
info('fcu_url = %s', rospy.get_param('mavros/fcu_url', '?'))
|
||||||
|
|
||||||
|
|
||||||
@@ -487,7 +494,7 @@ def check_vpe():
|
|||||||
failure('vision yaw weight is zero, change ATT_W_EXT_HDG parameter')
|
failure('vision yaw weight is zero, change ATT_W_EXT_HDG parameter')
|
||||||
else:
|
else:
|
||||||
info('vision yaw weight: %s', ff(vision_yaw_w))
|
info('vision yaw weight: %s', ff(vision_yaw_w))
|
||||||
fuse = get_param('LPE_FUSION')
|
fuse = int(get_param('LPE_FUSION'))
|
||||||
if not fuse & (1 << 2):
|
if not fuse & (1 << 2):
|
||||||
failure('vision position fusion is disabled, change LPE_FUSION parameter')
|
failure('vision position fusion is disabled, change LPE_FUSION parameter')
|
||||||
delay = get_param('LPE_VIS_DELAY')
|
delay = get_param('LPE_VIS_DELAY')
|
||||||
@@ -495,11 +502,22 @@ def check_vpe():
|
|||||||
failure('LPE_VIS_DELAY = %s, but it should be zero', delay)
|
failure('LPE_VIS_DELAY = %s, but it should be zero', delay)
|
||||||
info('LPE_VIS_XY = %s m, LPE_VIS_Z = %s m', get_paramf('LPE_VIS_XY'), get_paramf('LPE_VIS_Z'))
|
info('LPE_VIS_XY = %s m, LPE_VIS_Z = %s m', get_paramf('LPE_VIS_XY'), get_paramf('LPE_VIS_Z'))
|
||||||
elif est == 2:
|
elif est == 2:
|
||||||
fuse = get_param('EKF2_AID_MASK')
|
ev_ctrl = get_param('EKF2_EV_CTRL', strict=False)
|
||||||
if not fuse & (1 << 3):
|
if ev_ctrl is not None: # PX4 after v1.14
|
||||||
failure('vision position fusion is disabled, change EKF2_AID_MASK parameter')
|
ev_ctrl = int(ev_ctrl)
|
||||||
if not fuse & (1 << 4):
|
if not ev_ctrl & (1 << 0):
|
||||||
failure('vision yaw fusion is disabled, change EKF2_AID_MASK parameter')
|
failure('vision horizontal position fusion is disabled, change EKF2_EV_CTRL parameter')
|
||||||
|
if not ev_ctrl & (1 << 1):
|
||||||
|
failure('vision vertical position fusion is disabled, change EKF2_EV_CTRL parameter')
|
||||||
|
if not ev_ctrl & (1 << 3):
|
||||||
|
failure('vision yaw fusion is disabled, change EKF2_EV_CTRL parameter')
|
||||||
|
else: # PX4 before v1.14
|
||||||
|
fuse = int(get_param('EKF2_AID_MASK'))
|
||||||
|
if not fuse & (1 << 3):
|
||||||
|
failure('vision position fusion is disabled, change EKF2_AID_MASK parameter')
|
||||||
|
if not fuse & (1 << 4):
|
||||||
|
failure('vision yaw fusion is disabled, change EKF2_AID_MASK parameter')
|
||||||
|
|
||||||
delay = get_param('EKF2_EV_DELAY')
|
delay = get_param('EKF2_EV_DELAY')
|
||||||
if delay != 0:
|
if delay != 0:
|
||||||
failure('EKF2_EV_DELAY = %.2f, but it should be zero', delay)
|
failure('EKF2_EV_DELAY = %.2f, but it should be zero', delay)
|
||||||
@@ -606,8 +624,14 @@ def check_global_position():
|
|||||||
rospy.wait_for_message('mavros/global_position/global', NavSatFix, timeout=0.8)
|
rospy.wait_for_message('mavros/global_position/global', NavSatFix, timeout=0.8)
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
info('no global position')
|
info('no global position')
|
||||||
if get_param('SYS_MC_EST_GROUP') == 2 and (get_param('EKF2_AID_MASK', 0) & (1 << 0)):
|
if get_param('SYS_MC_EST_GROUP') == 2:
|
||||||
failure('enabled GPS fusion may suppress vision position aiding')
|
gps_ctrl = get_param('EKF2_GPS_CTRL', strict=False)
|
||||||
|
if gps_ctrl is not None: # PX4 after v1.14
|
||||||
|
if int(gps_ctrl) & (1 << 0):
|
||||||
|
failure('GPS fusion enabled may suppress vision position aiding, change EKF2_GPS_CTRL')
|
||||||
|
else: # PX4 before v1.14
|
||||||
|
if int(get_param('EKF2_AID_MASK', 0)) & (1 << 0):
|
||||||
|
failure('GPS fusion enabled may suppress vision position aiding, change EKF2_AID_MASK')
|
||||||
|
|
||||||
|
|
||||||
@check('Optical flow')
|
@check('Optical flow')
|
||||||
@@ -626,7 +650,7 @@ def check_optical_flow():
|
|||||||
failure('SENS_FLOW_ROT = %s, but it should be zero', rot)
|
failure('SENS_FLOW_ROT = %s, but it should be zero', rot)
|
||||||
est = get_param('SYS_MC_EST_GROUP')
|
est = get_param('SYS_MC_EST_GROUP')
|
||||||
if est == 1:
|
if est == 1:
|
||||||
fuse = get_param('LPE_FUSION')
|
fuse = int(get_param('LPE_FUSION'))
|
||||||
if not fuse & (1 << 1):
|
if not fuse & (1 << 1):
|
||||||
failure('optical flow fusion is disabled, change LPE_FUSION parameter')
|
failure('optical flow fusion is disabled, change LPE_FUSION parameter')
|
||||||
if not fuse & (1 << 1):
|
if not fuse & (1 << 1):
|
||||||
@@ -640,9 +664,14 @@ def check_optical_flow():
|
|||||||
get_paramf('LPE_FLW_R', 4),
|
get_paramf('LPE_FLW_R', 4),
|
||||||
get_paramf('LPE_FLW_RR', 4))
|
get_paramf('LPE_FLW_RR', 4))
|
||||||
elif est == 2:
|
elif est == 2:
|
||||||
fuse = get_param('EKF2_AID_MASK', 0)
|
of_ctrl = get_param('EKF2_OF_CTRL', strict=False)
|
||||||
if not fuse & (1 << 1):
|
if of_ctrl is not None: # PX4 after v1.14
|
||||||
failure('optical flow fusion is disabled, change EKF2_AID_MASK parameter')
|
if of_ctrl == 0:
|
||||||
|
failure('optical flow fusion is disabled, change EKF2_OF_CTRL')
|
||||||
|
else: # PX4 before v1.14
|
||||||
|
fuse = int(get_param('EKF2_AID_MASK', 0))
|
||||||
|
if not fuse & (1 << 1):
|
||||||
|
failure('optical flow fusion is disabled, change EKF2_AID_MASK parameter')
|
||||||
delay = get_param('EKF2_OF_DELAY', 0)
|
delay = get_param('EKF2_OF_DELAY', 0)
|
||||||
if delay != 0:
|
if delay != 0:
|
||||||
failure('EKF2_OF_DELAY = %.2f, but it should be zero', delay)
|
failure('EKF2_OF_DELAY = %.2f, but it should be zero', delay)
|
||||||
@@ -684,23 +713,26 @@ def check_rangefinder():
|
|||||||
|
|
||||||
est = get_param('SYS_MC_EST_GROUP')
|
est = get_param('SYS_MC_EST_GROUP')
|
||||||
if est == 1:
|
if est == 1:
|
||||||
fuse = get_param('LPE_FUSION', 0)
|
fuse = int(get_param('LPE_FUSION', 0))
|
||||||
if not fuse & (1 << 5):
|
if not fuse & (1 << 5):
|
||||||
info('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
|
info('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
|
||||||
else:
|
else:
|
||||||
info('"pub agl as lpos down" in LPE_FUSION is enabled, operating over flat surface')
|
info('"pub agl as lpos down" in LPE_FUSION is enabled, operating over flat surface')
|
||||||
|
|
||||||
elif est == 2:
|
elif est == 2:
|
||||||
hgt = get_param('EKF2_HGT_MODE')
|
hgt = get_param('EKF2_HGT_REF', strict=False)
|
||||||
|
if hgt is None: # PX4 before v1.14
|
||||||
|
hgt = get_param('EKF2_HGT_MODE')
|
||||||
if hgt != 2:
|
if hgt != 2:
|
||||||
info('EKF2_HGT_MODE != Range sensor, NOT operating over flat surface')
|
info('EKF2_HGT_MODE != Range sensor, NOT operating over flat surface')
|
||||||
else:
|
else:
|
||||||
info('EKF2_HGT_MODE = Range sensor, operating over flat surface')
|
info('EKF2_HGT_MODE = Range sensor, operating over flat surface')
|
||||||
aid = get_param('EKF2_RNG_AID')
|
aid = get_param('EKF2_RNG_AID', strict=False)
|
||||||
if aid != 1:
|
if aid is not None: # PX4 before v1.14
|
||||||
info('EKF2_RNG_AID != 1, range sensor aiding disabled')
|
if aid != 1:
|
||||||
else:
|
info('EKF2_RNG_AID != 1, range sensor aiding disabled')
|
||||||
info('EKF2_RNG_AID = 1, range sensor aiding enabled')
|
else:
|
||||||
|
info('EKF2_RNG_AID = 1, range sensor aiding enabled')
|
||||||
|
|
||||||
|
|
||||||
@check('Boot duration')
|
@check('Boot duration')
|
||||||
|
|||||||
@@ -40,6 +40,16 @@
|
|||||||
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
|
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
|
||||||
args="messages image_raw 5.0 image_raw_throttled" required="true"/>
|
args="messages image_raw 5.0 image_raw_throttled" required="true"/>
|
||||||
|
|
||||||
|
<node pkg="nodelet" type="nodelet" name="main_camera_nodelet_manager" args="manager" output="screen" required="true">
|
||||||
|
<param name="num_worker_threads" value="2"/>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node pkg="nodelet" type="nodelet" name="rectify" args="load image_proc/rectify main_camera_nodelet_manager" required="true">
|
||||||
|
<remap from="image_mono" to="main_camera/image_raw"/>
|
||||||
|
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||||
|
<remap from="image_rect" to="main_camera/image_rect"/>
|
||||||
|
</node>
|
||||||
|
|
||||||
<param name="test_module" value="$(find clover)/test/basic.py"/>
|
<param name="test_module" value="$(find clover)/test/basic.py"/>
|
||||||
<test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/>
|
<test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -1,17 +1,54 @@
|
|||||||
# PixHawk (px4fmu-v2), px4fmu-v3
|
# Source files: PX4-Autopilot/boards/**/nuttx-config/nsh/defconfig
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0011", ATTRS{product}=="PX4 FMU v2.x", SYMLINK+="px4fmu"
|
|
||||||
# PixRacer (px4fmu-v4)
|
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0012", ATTRS{product}=="PX4 FMU v4.x", SYMLINK+="px4fmu"
|
|
||||||
# px4fmu-v5
|
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0032", ATTRS{product}=="PX4 FMU v5.x", SYMLINK+="px4fmu"
|
|
||||||
# auav
|
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0021", ATTRS{product}=="PX4 AUAV x2.1", SYMLINK+="px4fmu"
|
|
||||||
# crazyflie
|
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0016", ATTRS{product}=="PX4 Crazyflie v2.0", SYMLINK+="px4fmu"
|
|
||||||
# px4fmu-v4pro
|
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0013", ATTRS{product}=="PX4 FMU v4.x PRO", SYMLINK+="px4fmu"
|
|
||||||
# Omnibus
|
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0001", ATTRS{product}=="PX4 OmnibusF4SD", SYMLINK+="px4fmu"
|
|
||||||
# CUAV X7 Pro
|
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="3163", ATTRS{idProduct}=="004c", ATTRS{product}=="PX4 CUAV X7Pro", SYMLINK+="px4fmu"
|
|
||||||
|
|
||||||
|
# Additional info:
|
||||||
|
# https://docs.px4.io/main/en/flight_controller/
|
||||||
|
# https://github.com/mavlink/qgroundcontrol/blob/master/src/comm/USBBoardInfo.json
|
||||||
|
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0001", ATTRS{product}=="PX4 GNF405", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0001", ATTRS{product}=="PX4 OmnibusF4SD", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0016", ATTRS{product}=="PX4 Crazyflie v2.0", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="1FC9", ATTRS{idProduct}=="001c", ATTRS{product}=="PX4 FMUK66 v3.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="1FC9", ATTRS{idProduct}=="001c", ATTRS{product}=="PX4 FMUK66 E", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="1FC9", ATTRS{idProduct}=="001d", ATTRS{product}=="PX4 FMURT1062 v1.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0001", ATTRS{product}=="DiatoneMambaF405 MK2", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="a32f", ATTRS{product}=="PX4 FMU ModalAI FCv1", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="a330", ATTRS{product}=="PX4 FMU ModalAI FCv2", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0012", ATTRS{product}=="PX4 FMU UVify Core", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3162", ATTRS{idProduct}=="0050", ATTRS{product}=="PX4 KakuteH7", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3162", ATTRS{idProduct}=="0050", ATTRS{product}=="PX4 KakuteH7v2", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3162", ATTRS{idProduct}=="004b", ATTRS{product}=="PX4 DurandalV1", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0050", ATTRS{product}=="PX4 KakuteF7", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3162", ATTRS{idProduct}=="0050", ATTRS{product}=="PX4 KakuteH7Mini-nand", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3162", ATTRS{idProduct}=="004E", ATTRS{product}=="PX4 PIX32V5", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0061", ATTRS{product}=="PX4 ATL Mantis-EDU", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3163", ATTRS{idProduct}=="004c", ATTRS{product}=="PX4 CUAV Nora", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3163", ATTRS{idProduct}=="004c", ATTRS{product}=="PX4 CUAV X7Pro", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="1B8C", ATTRS{idProduct}=="0036", ATTRS{product}=="MatekH743-mini", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="1B8C", ATTRS{idProduct}=="0036", ATTRS{product}=="MatekH743", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="120A", ATTRS{idProduct}=="1004", ATTRS{product}=="Matekgnssm9nf4", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="1209", ATTRS{idProduct}=="1013", ATTRS{product}=="MatekH743", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="0037", ATTRS{product}=="PX4 FMU SmartAP AIRLink", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="2DAE", ATTRS{idProduct}=="1058", ATTRS{product}=="CubeOrange+", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="2DAE", ATTRS{idProduct}=="1012", ATTRS{product}=="CubeYellow", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="2DAE", ATTRS{idProduct}=="1016", ATTRS{product}=="CubeOrange", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3185", ATTRS{idProduct}=="0035", ATTRS{product}=="PX4 FMU v6X.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3185", ATTRS{idProduct}=="0038", ATTRS{product}=="PX4 FMU v6C.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3185", ATTRS{idProduct}=="0033", ATTRS{product}=="PX4 FMU v5X.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="1B8C", ATTRS{idProduct}=="0036", ATTRS{product}=="PX4 FMU v6U.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0013", ATTRS{product}=="PX4 FMU v4.x PRO", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0011", ATTRS{product}=="PX4 FMU v2.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0012", ATTRS{product}=="PX4 FMU v4.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0032", ATTRS{product}=="PX4 FMU v5.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3162", ATTRS{idProduct}=="004b", ATTRS{product}=="PX4 SP RACING H7 EXTREME", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0030", ATTRS{product}=="MindPX FMU v2.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="3185", ATTRS{idProduct}=="0039", ATTRS{product}=="ARK FMU v6X.x", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0016", ATTRS{product}=="PX4 FreeFly RTK GPS", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="1024", ATTRS{product}=="mRoControlZeroH7 OEM", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="1017", ATTRS{product}=="mRoPixracerPro", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="1023", ATTRS{product}=="mRoControlZeroH7", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="008D", ATTRS{product}=="mRoControlZeroF7", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0021", ATTRS{product}=="PX4 AUAV X2.1", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="1022", ATTRS{product}=="mRoControlZero Classic", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0088", ATTRS{product}=="mRo x2.1-777", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="35a7", ATTRS{idProduct}=="0002", ATTRS{product}=="FCC-R1", SYMLINK+="px4fmu"
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="35a7", ATTRS{idProduct}=="0001", ATTRS{product}=="FCC-K1", SYMLINK+="px4fmu"
|
||||||
|
|||||||
BIN
docs/assets/stl/grip_left.stl
Normal file
BIN
docs/assets/stl/grip_left.stl
Normal file
Binary file not shown.
BIN
docs/assets/stl/grip_right.stl
Normal file
BIN
docs/assets/stl/grip_right.stl
Normal file
Binary file not shown.
@@ -9,6 +9,7 @@ Main frames in the `clover` package:
|
|||||||
* `base_link` is rigidly bound to the drone. It is shown by the simplified drone model on the image above;
|
* `base_link` is rigidly bound to the drone. It is shown by the simplified drone model on the image above;
|
||||||
* `body` is bound to the drone, but its Z axis points up regardless of the drone's pitch and roll. It is shown by the red, blue and green lines in the illustration;
|
* `body` is bound to the drone, but its Z axis points up regardless of the drone's pitch and roll. It is shown by the red, blue and green lines in the illustration;
|
||||||
* <a name="navigate_target"></a>`navigate_target` is bound to the current navigation target (as set by the [navigate](simple_offboard.md#navigate) service);
|
* <a name="navigate_target"></a>`navigate_target` is bound to the current navigation target (as set by the [navigate](simple_offboard.md#navigate) service);
|
||||||
|
* `terrain` is bound to the floor at the current drone position (see the [set_altitude](simple_offboard.md#set_altitude) service);
|
||||||
* `setpoint` is current position setpoint;
|
* `setpoint` is current position setpoint;
|
||||||
* `main_camera_optical` is the coordinate system, [linked to the main camera](camera_setup.md#frame);
|
* `main_camera_optical` is the coordinate system, [linked to the main camera](camera_setup.md#frame);
|
||||||
|
|
||||||
|
|||||||
@@ -198,6 +198,15 @@ This page contains models and drawings of some of the drone parts. They can be u
|
|||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
|
|
||||||
|
### 3D print
|
||||||
|
|
||||||
|
#### Mechanical gripper
|
||||||
|
|
||||||
|
* **Left claw**: [`grip_left.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/stl/grip_left.stl).
|
||||||
|
* **Right claw**: [`grip_right.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/stl/grip_right.stl).
|
||||||
|
|
||||||
|
Material: SBS Glass. Infill: 100%. Quantity: 1 pcs.
|
||||||
|
|
||||||
## Clover 4
|
## Clover 4
|
||||||
|
|
||||||
### 3D print
|
### 3D print
|
||||||
|
|||||||
@@ -39,17 +39,27 @@ In case of using EKF2 (official firmware):
|
|||||||
|
|
||||||
|Parameter|Value|Comment|
|
|Parameter|Value|Comment|
|
||||||
|-|-|-|
|
|-|-|-|
|
||||||
|`EKF2_AID_MASK`|26|Checkboxes: *flow* + *vision position* + *vision yaw*.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|
|`EKF2_AID_MASK`\*|26|Checkboxes: *flow* + *vision position* + *vision yaw*.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|
||||||
|`EKF2_OF_DELAY`|0||
|
|`EKF2_OF_DELAY`|0||
|
||||||
|`EKF2_OF_QMIN`|10||
|
|`EKF2_OF_QMIN`|10||
|
||||||
|`EKF2_OF_N_MIN`|0.05||
|
|`EKF2_OF_N_MIN`|0.05||
|
||||||
|`EKF2_OF_N_MAX`|0.2||
|
|`EKF2_OF_N_MAX`|0.2||
|
||||||
|`EKF2_HGT_MODE`|3 (*Vision*)|If the [rangefinder](laser.md) is present and flying over horizontal floor – 2 (*Range sensor*)|
|
|`EKF2_HGT_MODE`\*|3 (*Vision*)|If the [rangefinder](laser.md) is present and flying over horizontal floor – 2 (*Range sensor*)|
|
||||||
|`EKF2_EVA_NOISE`|0.1||
|
|`EKF2_EVA_NOISE`|0.1||
|
||||||
|`EKF2_EVP_NOISE`|0.1||
|
|`EKF2_EVP_NOISE`|0.1||
|
||||||
|`EKF2_EV_DELAY`|0||
|
|`EKF2_EV_DELAY`|0||
|
||||||
|`EKF2_MAG_TYPE`|5 (*None*)|Disabling usage of the magnetometer (when navigating indoor)|
|
|`EKF2_MAG_TYPE`|5 (*None*)|Disabling usage of the magnetometer (when navigating indoor)|
|
||||||
|
|
||||||
|
\* — starting from PX4 version 1.14, the parameters marked with an asterisk are replaced with the following:
|
||||||
|
|
||||||
|
|Parameter|Value|Comment|
|
||||||
|
|-|-|-|
|
||||||
|
|`EKF2_EV_CTRL`|11|Checkboxes: *Horizontal position* + *Vertical position* + *Yaw*|
|
||||||
|
|`EKF2_GPS_CTRL`|0|All checkboxes are disabled|
|
||||||
|
|`EKF2_BARO_CTRL`|0 (*Disabled*)|Barometer is disabled|
|
||||||
|
|`EKF2_OF_CTRL`|1 (*Enabled*)|Optical flow is enabled|
|
||||||
|
|`EKF2_HGT_REF`|3 (*Vision*)|If the [rangefinder](laser.md) is present and flying over horizontal floor – 2 (*Range sensor*)|
|
||||||
|
|
||||||
<!-- markdownlint-enable MD031 -->
|
<!-- markdownlint-enable MD031 -->
|
||||||
|
|
||||||
> **Info** See also: list of default parameters of the [Clover simulator](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
|
> **Info** See also: list of default parameters of the [Clover simulator](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
|
||||||
|
|||||||
@@ -66,7 +66,7 @@
|
|||||||
#### Камера направлена вверх, шлейф вперёд
|
#### Камера направлена вверх, шлейф вперёд
|
||||||
|
|
||||||
```xml
|
```xml
|
||||||
<arg name="direction_z" default="down"/>
|
<arg name="direction_z" default="up"/>
|
||||||
<arg name="direction_y" default="forward"/>
|
<arg name="direction_y" default="forward"/>
|
||||||
```
|
```
|
||||||
|
|
||||||
|
|||||||
@@ -11,6 +11,7 @@
|
|||||||
* `base_link` — координаты относительно квадрокоптера: схематичное изображение квадрокоптера на иллюстрации;
|
* `base_link` — координаты относительно квадрокоптера: схематичное изображение квадрокоптера на иллюстрации;
|
||||||
* `body` — координаты относительно квадрокоптера без учета наклонов по тангажу и крену: красная, синяя и зеленая линии на иллюстрации;
|
* `body` — координаты относительно квадрокоптера без учета наклонов по тангажу и крену: красная, синяя и зеленая линии на иллюстрации;
|
||||||
* <a name="navigate_target"></a>`navigate_target` – координаты точки, в которую сейчас летит дрон (с использованием [navigate](simple_offboard.md#navigate));
|
* <a name="navigate_target"></a>`navigate_target` – координаты точки, в которую сейчас летит дрон (с использованием [navigate](simple_offboard.md#navigate));
|
||||||
|
* `terrain` – координаты относительно пола в текущей позиции коптера (см. сервис [set_altitude](simple_offboard.md#set_altitude))
|
||||||
* `setpoint` – текущий setpoint по позиции;
|
* `setpoint` – текущий setpoint по позиции;
|
||||||
* `main_camera_optical` – система координат, [связанная с основной камерой](camera_setup.md#frame).
|
* `main_camera_optical` – система координат, [связанная с основной камерой](camera_setup.md#frame).
|
||||||
|
|
||||||
|
|||||||
@@ -200,13 +200,20 @@
|
|||||||
|
|
||||||
### 3D печать
|
### 3D печать
|
||||||
|
|
||||||
|
#### Механический захват
|
||||||
|
|
||||||
|
* **Левая клешня**: [`grip_left.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/stl/grip_left.stl).
|
||||||
|
* **Правая клешня**: [`grip_right.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/stl/grip_right.stl).
|
||||||
|
|
||||||
|
Материал: SBS Glass. Заполнение 100%. Количество: 1 шт.
|
||||||
|
|
||||||
#### Груз для магнитного захвата
|
#### Груз для магнитного захвата
|
||||||
|
|
||||||
* Груз для магнитного захвата: [`load_for_magnetic_grip.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/grip_load/load_for_magnetic_grip.stl)
|
* **Груз для магнитного захвата**: [`load_for_magnetic_grip.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/grip_load/load_for_magnetic_grip.stl).
|
||||||
* Дополнение-для-подставки-груза: [`add-on_for_load_support.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/grip_load/add-on_for_load_support.stl)
|
* **Дополнение для подставки груза**: [`add-on_for_load_support.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/grip_load/add-on_for_load_support.stl).
|
||||||
* Подставка под теннисный мяч для магнитного захвата: [`tennis_ball_stand_for_magnetic_grip.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/grip_load/tennis_ball_stand_for_magnetic_grip.stl).
|
* **Подставка под теннисный мяч для магнитного захвата**: [`tennis_ball_stand_for_magnetic_grip.stl`](https://github.com/CopterExpress/clover/raw/master/docs/assets/grip_load/tennis_ball_stand_for_magnetic_grip.stl).
|
||||||
|
|
||||||
Материал: PETG. Заполнение 100%. Количество: 1шт.
|
Материал: PETG. Заполнение 100%. Количество: 1 шт.
|
||||||
|
|
||||||
## Клевер 4
|
## Клевер 4
|
||||||
|
|
||||||
|
|||||||
@@ -39,17 +39,27 @@
|
|||||||
|
|
||||||
|Параметр|Значение|Примечание|
|
|Параметр|Значение|Примечание|
|
||||||
|-|-|-|
|
|-|-|-|
|
||||||
|`EKF2_AID_MASK`|26|Чекбоксы: *flow* + *vision position* + *vision yaw*.<br>Подробнее: [Optical Flow](optical_flow.md), [ArUco-маркеры](aruco_map.md), [GPS](gps.md).|
|
|`EKF2_AID_MASK`\*|26|Чекбоксы: *flow* + *vision position* + *vision yaw*.<br>Подробнее: [Optical Flow](optical_flow.md), [ArUco-маркеры](aruco_map.md), [GPS](gps.md).|
|
||||||
|`EKF2_OF_DELAY`|0||
|
|`EKF2_OF_DELAY`|0||
|
||||||
|`EKF2_OF_QMIN`|10||
|
|`EKF2_OF_QMIN`|10||
|
||||||
|`EKF2_OF_N_MIN`|0.05||
|
|`EKF2_OF_N_MIN`|0.05||
|
||||||
|`EKF2_OF_N_MAX`|0.2||
|
|`EKF2_OF_N_MAX`|0.2||
|
||||||
|`EKF2_HGT_MODE`|3 (*Vision*)|При наличии [дальномера](laser.md) и полете над ровным полом — 2 (*Range sensor*)|
|
|`EKF2_HGT_MODE`\*|3 (*Vision*)|При наличии [дальномера](laser.md) и полете над ровным полом — 2 (*Range sensor*)|
|
||||||
|`EKF2_EVA_NOISE`|0.1||
|
|`EKF2_EVA_NOISE`|0.1||
|
||||||
|`EKF2_EVP_NOISE`|0.1||
|
|`EKF2_EVP_NOISE`|0.1||
|
||||||
|`EKF2_EV_DELAY`|0||
|
|`EKF2_EV_DELAY`|0||
|
||||||
|`EKF2_MAG_TYPE`|5 (*None*)|Выключение магнитометра (при навигации внутри помещения)|
|
|`EKF2_MAG_TYPE`|5 (*None*)|Выключение магнитометра (при навигации внутри помещения)|
|
||||||
|
|
||||||
|
\* — начиная с версии PX4 1.14 помеченные звездочкой параметры заменены на следующие:
|
||||||
|
|
||||||
|
|Параметр|Значение|Примечание|
|
||||||
|
|-|-|-|
|
||||||
|
|`EKF2_EV_CTRL`|11|Чекбоксы: *Horizontal position* + *Vertical position* + *Yaw*|
|
||||||
|
|`EKF2_GPS_CTRL`|0|Все чекбоксы сняты|
|
||||||
|
|`EKF2_BARO_CTRL`|0 (*Disabled*)|Барометр отключен|
|
||||||
|
|`EKF2_OF_CTRL`|1 (*Enabled*)|Optical flow включен|
|
||||||
|
|`EKF2_HGT_REF`|3 (*Vision*)|При наличии [дальномера](laser.md) и полете над ровным полом — 2 (*Range sensor*)|
|
||||||
|
|
||||||
<!-- markdownlint-enable MD031 -->
|
<!-- markdownlint-enable MD031 -->
|
||||||
|
|
||||||
> **Info** См. также: список параметров по умолчанию в [симуляторе](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
|
> **Info** См. также: список параметров по умолчанию в [симуляторе](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
|
||||||
|
|||||||
@@ -23,6 +23,7 @@
|
|||||||
* **Корректная работа optical flow и всех его топиков, полет по optical flow**
|
* **Корректная работа optical flow и всех его топиков, полет по optical flow**
|
||||||
* **Полет по полю маркеров**
|
* **Полет по полю маркеров**
|
||||||
* **Корректная установка OpenCV – возможность использования из Python и C++**
|
* **Корректная установка OpenCV – возможность использования из Python и C++**
|
||||||
|
* Работа примера с компьютерном зрением: `red_circle.py`
|
||||||
* **Отсутствие неожиданного жора памяти и CPU (можно контролировать с помощью `selfcheck.py` или `htop`)**
|
* **Отсутствие неожиданного жора памяти и CPU (можно контролировать с помощью `selfcheck.py` или `htop`)**
|
||||||
* Автоматическая перекалибровка камеры при изменении разрешения
|
* Автоматическая перекалибровка камеры при изменении разрешения
|
||||||
|
|
||||||
@@ -60,7 +61,7 @@
|
|||||||
* **В фрейме `aruco_map`**
|
* **В фрейме `aruco_map`**
|
||||||
* **В фрейме `map`**
|
* **В фрейме `map`**
|
||||||
* **В фрейме `navigate_target`**
|
* **В фрейме `navigate_target`**
|
||||||
* **В фрейме `terrain`**.
|
* **В фрейме `terrain`**
|
||||||
* Корректное выполнения флипа
|
* Корректное выполнения флипа
|
||||||
* **Возможность лететь к отдельным маркерам в карте, которые вне кадра и в кадре**
|
* **Возможность лететь к отдельным маркерам в карте, которые вне кадра и в кадре**
|
||||||
* **Корректное детектирование статуса kill switch при выполнение команды с флагом `auto_arm`**
|
* **Корректное детектирование статуса kill switch при выполнение команды с флагом `auto_arm`**
|
||||||
@@ -103,6 +104,7 @@
|
|||||||
* ROS ноды не падают в случае потери всех соединений (удобно проверять с экраном)
|
* ROS ноды не падают в случае потери всех соединений (удобно проверять с экраном)
|
||||||
* Работает `rosshow`
|
* Работает `rosshow`
|
||||||
* Работает `espeak`
|
* Работает `espeak`
|
||||||
|
* Работает аргумент `rectify` в `main_camera.launch`
|
||||||
* *Работает LIRC*
|
* *Работает LIRC*
|
||||||
* *Работа iOS-пульта из коробки*
|
* *Работа iOS-пульта из коробки*
|
||||||
* *Работа Android-пульта из коробки*
|
* *Работа Android-пульта из коробки*
|
||||||
|
|||||||
Reference in New Issue
Block a user