mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-01 15:39:32 +00:00
Compare commits
76 Commits
terrain-fr
...
known_vert
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
a72cb67d03 | ||
|
|
8ac757598d | ||
|
|
25c3f25642 | ||
|
|
4877d0101b | ||
|
|
d4a83bdf58 | ||
|
|
8fd69e4ea5 | ||
|
|
c3625490b2 | ||
|
|
cb1773b708 | ||
|
|
5afbcff949 | ||
|
|
cf62364ac7 | ||
|
|
c7bf964ea5 | ||
|
|
f719406c8b | ||
|
|
72f8d901d5 | ||
|
|
5ec04bbefa | ||
|
|
393801b023 | ||
|
|
275023b455 | ||
|
|
a0322c55f2 | ||
|
|
b3b530c1c7 | ||
|
|
3662f512a7 | ||
|
|
277eb7297f | ||
|
|
e719b0f1e2 | ||
|
|
e65d380b4b | ||
|
|
8fe34e90e6 | ||
|
|
54ab5ab4b5 | ||
|
|
2cda68ae4a | ||
|
|
d24b6617a4 | ||
|
|
640ec1ee1a | ||
|
|
96ea78f141 | ||
|
|
5e3b07ff5e | ||
|
|
92748a760b | ||
|
|
8512e8a045 | ||
|
|
8b1b365e67 | ||
|
|
2cd77662df | ||
|
|
64f939d7ed | ||
|
|
9a8aa00bc7 | ||
|
|
3f3d1cd220 | ||
|
|
9c34d7722c | ||
|
|
19e0d725b0 | ||
|
|
6fafaf3184 | ||
|
|
8f09df6b34 | ||
|
|
c5d01c678a | ||
|
|
2b13aa02eb | ||
|
|
ec9ddf5fd2 | ||
|
|
c5399868cb | ||
|
|
a6cee773ab | ||
|
|
d03cfe00ca | ||
|
|
0fb101cc59 | ||
|
|
0d44ff3993 | ||
|
|
dc5da00abd | ||
|
|
4f00960db3 | ||
|
|
ce0b4eb428 | ||
|
|
ccbd1cbad9 | ||
|
|
4b397670a1 | ||
|
|
89bfc150f3 | ||
|
|
6b05cb34e5 | ||
|
|
22293c2220 | ||
|
|
38a3f656ab | ||
|
|
2e79979411 | ||
|
|
b165e154f5 | ||
|
|
99fad312c5 | ||
|
|
ee17a3bada | ||
|
|
1461dd22f4 | ||
|
|
2c07bbffe3 | ||
|
|
0b62f677af | ||
|
|
070c23be53 | ||
|
|
c907e6041a | ||
|
|
69d5d1e521 | ||
|
|
1700ad24df | ||
|
|
6361984794 | ||
|
|
7f31fdd320 | ||
|
|
f9450fe03d | ||
|
|
b41cb6b581 | ||
|
|
b855c4586a | ||
|
|
26245dfb42 | ||
|
|
d6f9327ede | ||
|
|
0f5f111f46 |
7
.github/workflows/docs.yml
vendored
7
.github/workflows/docs.yml
vendored
@@ -11,10 +11,6 @@ permissions:
|
|||||||
pages: write
|
pages: write
|
||||||
id-token: write
|
id-token: write
|
||||||
|
|
||||||
concurrency:
|
|
||||||
group: "pages"
|
|
||||||
cancel-in-progress: true
|
|
||||||
|
|
||||||
defaults:
|
defaults:
|
||||||
run:
|
run:
|
||||||
shell: bash
|
shell: bash
|
||||||
@@ -75,6 +71,9 @@ jobs:
|
|||||||
|
|
||||||
deploy-docs:
|
deploy-docs:
|
||||||
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
|
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
|
||||||
|
concurrency:
|
||||||
|
group: "pages"
|
||||||
|
cancel-in-progress: true
|
||||||
environment:
|
environment:
|
||||||
name: github-pages
|
name: github-pages
|
||||||
url: ${{ steps.deployment.outputs.page_url }}
|
url: ${{ steps.deployment.outputs.page_url }}
|
||||||
|
|||||||
@@ -43,7 +43,8 @@ It's recommended to run it within the same nodelet manager with the camera nodel
|
|||||||
* `~frame_id_prefix` (*string*) – prefix for TF transforms names, marker's ID is appended (default: `aruco_`)
|
* `~frame_id_prefix` (*string*) – prefix for TF transforms names, marker's ID is appended (default: `aruco_`)
|
||||||
* `~length` (*double*) – markers' sides length
|
* `~length` (*double*) – markers' sides length
|
||||||
* `~length_override` (*map*) – lengths of markers with specified ids
|
* `~length_override` (*map*) – lengths of markers with specified ids
|
||||||
* `~known_tilt` (*string*) – known tilt (pitch and roll) of all the markers as a frame
|
* `~known_vertical` (*string*) – known vertical (Z axis) of all the markers as a frame
|
||||||
|
* `~flip_vertical` – flip vertical vector
|
||||||
|
|
||||||
### Topics
|
### Topics
|
||||||
|
|
||||||
@@ -71,7 +72,8 @@ It's recommended to run it within the same nodelet manager with the camera nodel
|
|||||||
|
|
||||||
* `~map` – path to text file with markers list
|
* `~map` – path to text file with markers list
|
||||||
* `~frame_id` – published frame id (default: `aruco_map`)
|
* `~frame_id` – published frame id (default: `aruco_map`)
|
||||||
* `~known_tilt` – known tilt (pitch and roll) of markers map as a frame
|
* `~known_vertical` – known vertical (Z axis) of markers map as a frame
|
||||||
|
* `~flip_vertical` – flip vertical vector
|
||||||
* `~image_width` – debug image width (default: 2000)
|
* `~image_width` – debug image width (default: 2000)
|
||||||
* `~image_height` – debug image height (default: 2000)
|
* `~image_height` – debug image height (default: 2000)
|
||||||
* `~image_margin` – debug image margin (default: 200)
|
* `~image_margin` – debug image margin (default: 200)
|
||||||
|
|||||||
@@ -1,5 +1,5 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<package format="2">
|
<package format="3">
|
||||||
<name>aruco_pose</name>
|
<name>aruco_pose</name>
|
||||||
<version>0.23.0</version>
|
<version>0.23.0</version>
|
||||||
<description>Positioning with ArUco markers</description>
|
<description>Positioning with ArUco markers</description>
|
||||||
@@ -28,6 +28,8 @@
|
|||||||
<depend>sensor_msgs</depend>
|
<depend>sensor_msgs</depend>
|
||||||
<depend>rostest</depend>
|
<depend>rostest</depend>
|
||||||
<depend>dynamic_reconfigure</depend>
|
<depend>dynamic_reconfigure</depend>
|
||||||
|
<depend condition="$ROS_PYTHON_VERSION == 2">python-docopt</depend>
|
||||||
|
<depend condition="$ROS_PYTHON_VERSION == 3">python3-docopt</depend>
|
||||||
|
|
||||||
<test_depend>image_publisher</test_depend>
|
<test_depend>image_publisher</test_depend>
|
||||||
<test_depend>ros_pytest</test_depend>
|
<test_depend>ros_pytest</test_depend>
|
||||||
|
|||||||
@@ -71,11 +71,12 @@ private:
|
|||||||
ros::Publisher markers_pub_, vis_markers_pub_;
|
ros::Publisher markers_pub_, vis_markers_pub_;
|
||||||
ros::Subscriber map_markers_sub_;
|
ros::Subscriber map_markers_sub_;
|
||||||
ros::ServiceServer set_markers_srv_;
|
ros::ServiceServer set_markers_srv_;
|
||||||
bool estimate_poses_, send_tf_, auto_flip_;
|
bool estimate_poses_, send_tf_, flip_vertical_, auto_flip_, use_map_markers_;
|
||||||
|
bool waiting_for_map_;
|
||||||
double length_;
|
double length_;
|
||||||
ros::Duration transform_timeout_;
|
ros::Duration transform_timeout_;
|
||||||
std::unordered_map<int, double> length_override_;
|
std::unordered_map<int, double> length_override_;
|
||||||
std::string frame_id_prefix_, known_tilt_;
|
std::string frame_id_prefix_, known_vertical_;
|
||||||
Mat camera_matrix_, dist_coeffs_;
|
Mat camera_matrix_, dist_coeffs_;
|
||||||
aruco_pose::MarkerArray array_;
|
aruco_pose::MarkerArray array_;
|
||||||
std::unordered_set<int> map_markers_ids_;
|
std::unordered_set<int> map_markers_ids_;
|
||||||
@@ -95,6 +96,8 @@ public:
|
|||||||
dictionary = nh_priv_.param("dictionary", 2);
|
dictionary = nh_priv_.param("dictionary", 2);
|
||||||
estimate_poses_ = nh_priv_.param("estimate_poses", true);
|
estimate_poses_ = nh_priv_.param("estimate_poses", true);
|
||||||
send_tf_ = nh_priv_.param("send_tf", true);
|
send_tf_ = nh_priv_.param("send_tf", true);
|
||||||
|
use_map_markers_ = nh_priv_.param("use_map_markers", false);
|
||||||
|
waiting_for_map_ = use_map_markers_;
|
||||||
if (estimate_poses_ && !nh_priv_.getParam("length", length_)) {
|
if (estimate_poses_ && !nh_priv_.getParam("length", length_)) {
|
||||||
NODELET_FATAL("can't estimate marker's poses as ~length parameter is not defined");
|
NODELET_FATAL("can't estimate marker's poses as ~length parameter is not defined");
|
||||||
ros::shutdown();
|
ros::shutdown();
|
||||||
@@ -102,7 +105,8 @@ public:
|
|||||||
readLengthOverride(nh_priv_);
|
readLengthOverride(nh_priv_);
|
||||||
transform_timeout_ = ros::Duration(nh_priv_.param("transform_timeout", 0.02));
|
transform_timeout_ = ros::Duration(nh_priv_.param("transform_timeout", 0.02));
|
||||||
|
|
||||||
known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
|
known_vertical_ = nh_priv_.param("known_vertical", nh_priv_.param("known_tilt", std::string(""))); // known_tilt is an old name
|
||||||
|
flip_vertical_ = nh_priv_.param<bool>("flip_vertical", false);
|
||||||
auto_flip_ = nh_priv_.param("auto_flip", false);
|
auto_flip_ = nh_priv_.param("auto_flip", false);
|
||||||
|
|
||||||
frame_id_prefix_ = nh_priv_.param<std::string>("frame_id_prefix", "aruco_");
|
frame_id_prefix_ = nh_priv_.param<std::string>("frame_id_prefix", "aruco_");
|
||||||
@@ -133,6 +137,7 @@ private:
|
|||||||
void imageCallback(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr &cinfo)
|
void imageCallback(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr &cinfo)
|
||||||
{
|
{
|
||||||
if (!enabled_) return;
|
if (!enabled_) return;
|
||||||
|
if (waiting_for_map_) return;
|
||||||
|
|
||||||
Mat image = cv_bridge::toCvShare(msg, "bgr8")->image;
|
Mat image = cv_bridge::toCvShare(msg, "bgr8")->image;
|
||||||
|
|
||||||
@@ -140,7 +145,7 @@ private:
|
|||||||
vector<vector<cv::Point2f>> corners, rejected;
|
vector<vector<cv::Point2f>> corners, rejected;
|
||||||
vector<cv::Vec3d> rvecs, tvecs;
|
vector<cv::Vec3d> rvecs, tvecs;
|
||||||
vector<cv::Point3f> obj_points;
|
vector<cv::Point3f> obj_points;
|
||||||
geometry_msgs::TransformStamped snap_to;
|
geometry_msgs::TransformStamped vertical;
|
||||||
|
|
||||||
// Detect markers
|
// Detect markers
|
||||||
cv::aruco::detectMarkers(image, dictionary_, corners, ids, parameters_, rejected);
|
cv::aruco::detectMarkers(image, dictionary_, corners, ids, parameters_, rejected);
|
||||||
@@ -175,12 +180,12 @@ private:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!known_tilt_.empty()) {
|
if (!known_vertical_.empty()) {
|
||||||
try {
|
try {
|
||||||
snap_to = tf_buffer_->lookupTransform(msg->header.frame_id, known_tilt_,
|
vertical = tf_buffer_->lookupTransform(msg->header.frame_id, known_vertical_,
|
||||||
msg->header.stamp, transform_timeout_);
|
msg->header.stamp, transform_timeout_);
|
||||||
} catch (const tf2::TransformException& e) {
|
} catch (const tf2::TransformException& e) {
|
||||||
NODELET_WARN_THROTTLE(5, "can't snap: %s", e.what());
|
NODELET_WARN_THROTTLE(5, "can't retrieve known vertical: %s", e.what());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -201,9 +206,9 @@ private:
|
|||||||
if (estimate_poses_) {
|
if (estimate_poses_) {
|
||||||
fillPose(marker.pose, rvecs[i], tvecs[i]);
|
fillPose(marker.pose, rvecs[i], tvecs[i]);
|
||||||
|
|
||||||
// snap orientation (if enabled and snap frame available)
|
// apply known vertical (if enabled and vertical frame available)
|
||||||
if (!known_tilt_.empty() && !snap_to.header.frame_id.empty()) {
|
if (!known_vertical_.empty() && !vertical.header.frame_id.empty()) {
|
||||||
snapOrientation(marker.pose.orientation, snap_to.transform.rotation, auto_flip_);
|
applyVertical(marker.pose.orientation, vertical.transform.rotation, false, auto_flip_);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (send_tf_) {
|
if (send_tf_) {
|
||||||
@@ -395,7 +400,13 @@ private:
|
|||||||
map_markers_ids_.clear();
|
map_markers_ids_.clear();
|
||||||
for (auto const& marker : msg.markers) {
|
for (auto const& marker : msg.markers) {
|
||||||
map_markers_ids_.insert(marker.id);
|
map_markers_ids_.insert(marker.id);
|
||||||
|
if (use_map_markers_) {
|
||||||
|
if (length_override_.find(marker.id) == length_override_.end()) {
|
||||||
|
length_override_[marker.id] = marker.length;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
waiting_for_map_ = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void paramCallback(aruco_pose::DetectorConfig &config, uint32_t level)
|
void paramCallback(aruco_pose::DetectorConfig &config, uint32_t level)
|
||||||
|
|||||||
@@ -81,9 +81,9 @@ private:
|
|||||||
bool enabled_ = true;
|
bool enabled_ = true;
|
||||||
std::string type_;
|
std::string type_;
|
||||||
visualization_msgs::MarkerArray vis_array_;
|
visualization_msgs::MarkerArray vis_array_;
|
||||||
std::string known_tilt_, map_, markers_frame_, markers_parent_frame_;
|
std::string known_vertical_, map_, markers_frame_, markers_parent_frame_;
|
||||||
int image_width_, image_height_, image_margin_;
|
int image_width_, image_height_, image_margin_;
|
||||||
bool auto_flip_, image_axis_;
|
bool flip_vertical_, auto_flip_, image_axis_;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
virtual void onInit()
|
virtual void onInit()
|
||||||
@@ -104,7 +104,8 @@ public:
|
|||||||
|
|
||||||
type_ = nh_priv_.param<std::string>("type", "map");
|
type_ = nh_priv_.param<std::string>("type", "map");
|
||||||
transform_.child_frame_id = nh_priv_.param<std::string>("frame_id", "aruco_map");
|
transform_.child_frame_id = nh_priv_.param<std::string>("frame_id", "aruco_map");
|
||||||
known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
|
known_vertical_ = nh_priv_.param("known_vertical", nh_priv_.param("known_tilt", std::string(""))); // known_tilt is an old name
|
||||||
|
flip_vertical_ = nh_priv_.param<bool>("flip_vertical", false);
|
||||||
auto_flip_ = nh_priv_.param("auto_flip", false);
|
auto_flip_ = nh_priv_.param("auto_flip", false);
|
||||||
image_width_ = nh_priv_.param("image_width" , 2000);
|
image_width_ = nh_priv_.param("image_width" , 2000);
|
||||||
image_height_ = nh_priv_.param("image_height", 2000);
|
image_height_ = nh_priv_.param("image_height", 2000);
|
||||||
@@ -177,7 +178,7 @@ public:
|
|||||||
corners.push_back(marker_corners);
|
corners.push_back(marker_corners);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (known_tilt_.empty()) {
|
if (known_vertical_.empty()) {
|
||||||
// simple estimation
|
// simple estimation
|
||||||
valid = cv::aruco::estimatePoseBoard(corners, ids, board_, camera_matrix_, dist_coeffs_,
|
valid = cv::aruco::estimatePoseBoard(corners, ids, board_, camera_matrix_, dist_coeffs_,
|
||||||
rvec, tvec, false);
|
rvec, tvec, false);
|
||||||
@@ -191,7 +192,7 @@ public:
|
|||||||
|
|
||||||
} else {
|
} else {
|
||||||
Mat obj_points, img_points;
|
Mat obj_points, img_points;
|
||||||
// estimation with "snapping"
|
// estimation with known vertical
|
||||||
cv::aruco::getBoardObjectAndImagePoints(board_, corners, ids, obj_points, img_points);
|
cv::aruco::getBoardObjectAndImagePoints(board_, corners, ids, obj_points, img_points);
|
||||||
if (obj_points.empty()) goto publish_debug;
|
if (obj_points.empty()) goto publish_debug;
|
||||||
|
|
||||||
@@ -203,11 +204,11 @@ public:
|
|||||||
|
|
||||||
fillTransform(transform_.transform, rvec, tvec);
|
fillTransform(transform_.transform, rvec, tvec);
|
||||||
try {
|
try {
|
||||||
geometry_msgs::TransformStamped snap_to = tf_buffer_.lookupTransform(markers->header.frame_id,
|
geometry_msgs::TransformStamped vertical = tf_buffer_.lookupTransform(markers->header.frame_id,
|
||||||
known_tilt_, markers->header.stamp, ros::Duration(0.02));
|
known_vertical_, markers->header.stamp, ros::Duration(0.02));
|
||||||
snapOrientation(transform_.transform.rotation, snap_to.transform.rotation, auto_flip_);
|
applyVertical(transform_.transform.rotation, vertical.transform.rotation, flip_vertical_, auto_flip_);
|
||||||
} catch (const tf2::TransformException& e) {
|
} catch (const tf2::TransformException& e) {
|
||||||
NODELET_WARN_THROTTLE(1, "can't snap: %s", e.what());
|
NODELET_WARN_THROTTLE(1, "can't retrieve known vertical: %s", e.what());
|
||||||
}
|
}
|
||||||
|
|
||||||
geometry_msgs::TransformStamped shift;
|
geometry_msgs::TransformStamped shift;
|
||||||
@@ -503,7 +504,7 @@ publish_debug:
|
|||||||
vis_marker.pose.position.x = x;
|
vis_marker.pose.position.x = x;
|
||||||
vis_marker.pose.position.y = y;
|
vis_marker.pose.position.y = y;
|
||||||
vis_marker.pose.position.z = z;
|
vis_marker.pose.position.z = z;
|
||||||
tf::quaternionTFToMsg(q, marker.pose.orientation);
|
tf::quaternionTFToMsg(q, vis_marker.pose.orientation);
|
||||||
vis_marker.frame_locked = true;
|
vis_marker.frame_locked = true;
|
||||||
vis_array_.markers.push_back(vis_marker);
|
vis_array_.markers.push_back(vis_marker);
|
||||||
|
|
||||||
|
|||||||
@@ -106,26 +106,25 @@ inline bool isFlipped(tf::Quaternion& q)
|
|||||||
return (abs(pitch) > M_PI / 2) || (abs(roll) > M_PI / 2);
|
return (abs(pitch) > M_PI / 2) || (abs(roll) > M_PI / 2);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Set roll and pitch from "from" to "to", keeping yaw */
|
/* Apply a vertical to an orientation */
|
||||||
inline void snapOrientation(geometry_msgs::Quaternion& to, const geometry_msgs::Quaternion& from, bool auto_flip = false)
|
inline void applyVertical(geometry_msgs::Quaternion& orientation, const geometry_msgs::Quaternion& vertical,
|
||||||
|
bool flip_vertical = false, bool auto_flip = false) // editorconfig-checker-disable-line
|
||||||
{
|
{
|
||||||
tf::Quaternion _from, _to;
|
tf::Quaternion _vertical, _orientation;
|
||||||
tf::quaternionMsgToTF(from, _from);
|
tf::quaternionMsgToTF(vertical, _vertical);
|
||||||
tf::quaternionMsgToTF(to, _to);
|
tf::quaternionMsgToTF(orientation, _orientation);
|
||||||
|
|
||||||
if (auto_flip) {
|
if (flip_vertical || (auto_flip && !isFlipped(_orientation))) {
|
||||||
if (!isFlipped(_from)) {
|
static const tf::Quaternion flip = tf::createQuaternionFromRPY(M_PI, 0, 0);
|
||||||
static const tf::Quaternion flip = tf::createQuaternionFromRPY(M_PI, 0, 0);
|
_vertical *= flip; // flip vertical
|
||||||
_from *= flip; // flip "from"
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
auto diff = tf::Matrix3x3(_to).transposeTimes(tf::Matrix3x3(_from));
|
auto diff = tf::Matrix3x3(_orientation).transposeTimes(tf::Matrix3x3(_vertical));
|
||||||
double _, yaw;
|
double _, yaw;
|
||||||
diff.getRPY(_, _, yaw);
|
diff.getRPY(_, _, yaw);
|
||||||
auto q = tf::createQuaternionFromRPY(0, 0, -yaw);
|
auto q = tf::createQuaternionFromRPY(0, 0, -yaw);
|
||||||
_from = _from * q; // set yaw from "to" to "from"
|
_vertical = _vertical * q; // set yaw from orientation to vertical
|
||||||
tf::quaternionTFToMsg(_from, to); // set "from" to "to"
|
tf::quaternionTFToMsg(_vertical, orientation); // set vertical to orientation
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void transformToPose(const geometry_msgs::Transform& transform, geometry_msgs::Pose& pose)
|
inline void transformToPose(const geometry_msgs::Transform& transform, geometry_msgs::Pose& pose)
|
||||||
|
|||||||
@@ -6,7 +6,7 @@ import tf2_geometry_msgs
|
|||||||
from geometry_msgs.msg import PoseWithCovarianceStamped
|
from geometry_msgs.msg import PoseWithCovarianceStamped
|
||||||
from sensor_msgs.msg import Image
|
from sensor_msgs.msg import Image
|
||||||
from aruco_pose.msg import MarkerArray
|
from aruco_pose.msg import MarkerArray
|
||||||
from visualization_msgs.msg import MarkerArray as VisMarkerArray
|
from visualization_msgs.msg import MarkerArray as VisMarkerArray, Marker as VisMarker
|
||||||
|
|
||||||
|
|
||||||
@pytest.fixture
|
@pytest.fixture
|
||||||
@@ -199,6 +199,36 @@ def test_map_markers(node):
|
|||||||
|
|
||||||
def test_map_visualization(node):
|
def test_map_visualization(node):
|
||||||
vis = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)
|
vis = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)
|
||||||
|
assert len(vis.markers) == 7
|
||||||
|
assert vis.markers[0].header.frame_id == 'aruco_map'
|
||||||
|
assert vis.markers[0].type == VisMarker.CUBE
|
||||||
|
assert vis.markers[0].action == VisMarker.ADD
|
||||||
|
assert vis.markers[0].pose.position.x == 0
|
||||||
|
assert vis.markers[0].pose.position.y == 0
|
||||||
|
assert vis.markers[0].pose.position.z == 0
|
||||||
|
assert vis.markers[0].pose.orientation.x == 0
|
||||||
|
assert vis.markers[0].pose.orientation.y == 0
|
||||||
|
assert vis.markers[0].pose.orientation.z == 0
|
||||||
|
assert vis.markers[0].pose.orientation.w == 1
|
||||||
|
assert vis.markers[0].scale.x == approx(0.33)
|
||||||
|
assert vis.markers[0].scale.y == approx(0.33)
|
||||||
|
assert vis.markers[0].scale.z == approx(0.001)
|
||||||
|
assert vis.markers[1].pose.position.x == 1
|
||||||
|
assert vis.markers[1].pose.position.y == 0
|
||||||
|
assert vis.markers[1].pose.position.z == 0
|
||||||
|
assert vis.markers[1].pose.orientation.x == 0
|
||||||
|
assert vis.markers[1].pose.orientation.y == 0
|
||||||
|
assert vis.markers[1].pose.orientation.z == 0
|
||||||
|
assert vis.markers[1].pose.orientation.w == 1
|
||||||
|
# non-zero yaw marker:
|
||||||
|
assert vis.markers[4].scale.x == approx(0.5)
|
||||||
|
assert vis.markers[4].pose.position.x == approx(0.5)
|
||||||
|
assert vis.markers[4].pose.position.y == 2
|
||||||
|
assert vis.markers[4].pose.position.z == 0
|
||||||
|
assert vis.markers[4].pose.orientation.x == 0
|
||||||
|
assert vis.markers[4].pose.orientation.y == 0
|
||||||
|
assert vis.markers[4].pose.orientation.z == approx(0.5646424733950354)
|
||||||
|
assert vis.markers[4].pose.orientation.w == approx(0.8253356149096783)
|
||||||
|
|
||||||
def test_map_debug(node):
|
def test_map_debug(node):
|
||||||
img = rospy.wait_for_message('aruco_map/debug', Image, timeout=5)
|
img = rospy.wait_for_message('aruco_map/debug', Image, timeout=5)
|
||||||
|
|||||||
@@ -151,6 +151,9 @@ catkin_make run_tests #&& catkin_test_results
|
|||||||
echo_stamp "Change permissions for catkin_ws"
|
echo_stamp "Change permissions for catkin_ws"
|
||||||
chown -Rf pi:pi /home/pi/catkin_ws
|
chown -Rf pi:pi /home/pi/catkin_ws
|
||||||
|
|
||||||
|
echo_stamp "Update www"
|
||||||
|
sudo -u pi sh -c ". devel/setup.sh && rosrun clover www"
|
||||||
|
|
||||||
echo_stamp "Make \$HOME/examples symlink"
|
echo_stamp "Make \$HOME/examples symlink"
|
||||||
ln -s "$(catkin_find clover examples --first-only)" /home/pi
|
ln -s "$(catkin_find clover examples --first-only)" /home/pi
|
||||||
chown -Rf pi:pi /home/pi/examples
|
chown -Rf pi:pi /home/pi/examples
|
||||||
|
|||||||
@@ -2,6 +2,7 @@
|
|||||||
|
|
||||||
# validate all required modules installed
|
# validate all required modules installed
|
||||||
|
|
||||||
|
import os
|
||||||
import rospy
|
import rospy
|
||||||
from geometry_msgs.msg import PoseStamped
|
from geometry_msgs.msg import PoseStamped
|
||||||
from sensor_msgs.msg import Range, BatteryState
|
from sensor_msgs.msg import Range, BatteryState
|
||||||
@@ -22,6 +23,7 @@ from clover.srv import GetTelemetry, Navigate, NavigateGlobal, SetPosition, SetV
|
|||||||
from led_msgs.srv import SetLEDs
|
from led_msgs.srv import SetLEDs
|
||||||
from led_msgs.msg import LEDStateArray, LEDState
|
from led_msgs.msg import LEDStateArray, LEDState
|
||||||
from aruco_pose.msg import Marker, MarkerArray, Point2D
|
from aruco_pose.msg import Marker, MarkerArray, Point2D
|
||||||
|
from clover import long_callback
|
||||||
|
|
||||||
import dynamic_reconfigure.client
|
import dynamic_reconfigure.client
|
||||||
|
|
||||||
@@ -31,9 +33,12 @@ import tf2_geometry_msgs
|
|||||||
import VL53L1X
|
import VL53L1X
|
||||||
import pymavlink
|
import pymavlink
|
||||||
from pymavlink import mavutil
|
from pymavlink import mavutil
|
||||||
import rpi_ws281x
|
|
||||||
import pigpio
|
|
||||||
# from espeak import espeak
|
# from espeak import espeak
|
||||||
from pyzbar import pyzbar
|
from pyzbar import pyzbar
|
||||||
|
import docopt
|
||||||
|
|
||||||
print(cv2.getBuildInformation())
|
print(cv2.getBuildInformation())
|
||||||
|
|
||||||
|
if not os.environ.get('VM'):
|
||||||
|
import rpi_ws281x
|
||||||
|
import pigpio
|
||||||
|
|||||||
@@ -6,16 +6,10 @@ set -ex
|
|||||||
|
|
||||||
# validate required software is installed
|
# validate required software is installed
|
||||||
|
|
||||||
python --version
|
|
||||||
python2 --version
|
python2 --version
|
||||||
python3 --version
|
python3 --version
|
||||||
ipython --version
|
|
||||||
ipython3 --version
|
ipython3 --version
|
||||||
|
|
||||||
# ptvsd does not have a stand-alone binary
|
|
||||||
python -m ptvsd --version
|
|
||||||
python3 -m ptvsd --version
|
|
||||||
|
|
||||||
node -v
|
node -v
|
||||||
npm -v
|
npm -v
|
||||||
|
|
||||||
@@ -25,42 +19,77 @@ lsof -v
|
|||||||
git --version
|
git --version
|
||||||
vim --version
|
vim --version
|
||||||
pip --version
|
pip --version
|
||||||
pip2 --version
|
|
||||||
pip3 --version
|
pip3 --version
|
||||||
tcpdump --version
|
tcpdump --version
|
||||||
monkey --version
|
monkey --version
|
||||||
pigpiod -v
|
|
||||||
i2cdetect -V
|
|
||||||
butterfly -h
|
|
||||||
# espeak --version
|
# espeak --version
|
||||||
mjpg_streamer --version
|
|
||||||
systemctl --version
|
systemctl --version
|
||||||
|
|
||||||
|
if [ -z $VM ]; then
|
||||||
|
# rpi only software
|
||||||
|
python --version
|
||||||
|
ipython --version
|
||||||
|
pip2 --version
|
||||||
|
# `python` is python2 for now
|
||||||
|
[[ $(python -c 'import sys;print(sys.version_info.major)') == "2" ]]
|
||||||
|
|
||||||
|
# ptvsd does not have a stand-alone binary
|
||||||
|
python -m ptvsd --version
|
||||||
|
python3 -m ptvsd --version
|
||||||
|
|
||||||
|
pigpiod -v
|
||||||
|
i2cdetect -V
|
||||||
|
butterfly -h
|
||||||
|
mjpg_streamer --version
|
||||||
|
fi
|
||||||
|
|
||||||
# ros stuff
|
# ros stuff
|
||||||
|
|
||||||
roscore -h
|
roscore -h
|
||||||
rosversion clover
|
rosversion clover
|
||||||
rosversion aruco_pose
|
rosversion aruco_pose
|
||||||
rosversion vl53l1x
|
|
||||||
rosversion mavros
|
rosversion mavros
|
||||||
rosversion mavros_extras
|
rosversion mavros_extras
|
||||||
rosversion ws281x
|
rosversion ws281x
|
||||||
rosversion led_msgs
|
rosversion led_msgs
|
||||||
rosversion dynamic_reconfigure
|
rosversion dynamic_reconfigure
|
||||||
rosversion tf2_web_republisher
|
rosversion tf2_web_republisher
|
||||||
rosversion compressed_image_transport
|
rosversion rosbridge_server
|
||||||
rosversion rosbridge_suite
|
|
||||||
rosversion rosserial
|
|
||||||
rosversion usb_cam
|
rosversion usb_cam
|
||||||
rosversion cv_camera
|
rosversion cv_camera
|
||||||
rosversion web_video_server
|
rosversion web_video_server
|
||||||
rosversion rosshow
|
|
||||||
rosversion nodelet
|
rosversion nodelet
|
||||||
rosversion image_view
|
rosversion image_view
|
||||||
|
|
||||||
# validate some versions
|
|
||||||
[[ $(rosversion cv_camera) == "0.5.1" ]] # patched version with init fix
|
|
||||||
[[ $(rosversion ws281x) == "0.0.13" ]]
|
[[ $(rosversion ws281x) == "0.0.13" ]]
|
||||||
|
|
||||||
|
if [ -z $VM ]; then
|
||||||
|
rosversion compressed_image_transport
|
||||||
|
rosversion rosshow
|
||||||
|
rosversion vl53l1x
|
||||||
|
rosversion rosserial
|
||||||
|
[[ $(rosversion cv_camera) == "0.5.1" ]] # patched version with init fix
|
||||||
|
fi
|
||||||
|
|
||||||
|
# determine user home directory
|
||||||
|
[ $VM ] && H="/home/clover" || H="/home/pi"
|
||||||
|
|
||||||
|
# test basic ros tool work
|
||||||
|
source $H/catkin_ws/devel/setup.bash
|
||||||
|
roscd
|
||||||
|
rosrun
|
||||||
|
rosmsg
|
||||||
|
rossrv
|
||||||
|
rosnode || [ $? -eq 64 ] # usage output code is 64
|
||||||
|
rostopic || [ $? -eq 64 ]
|
||||||
|
rosservice || [ $? -eq 64 ]
|
||||||
|
rosparam
|
||||||
|
roslaunch -h
|
||||||
|
|
||||||
# validate examples are present
|
# validate examples are present
|
||||||
[[ $(ls /home/pi/examples/*) ]]
|
[[ $(ls $H/examples/*) ]]
|
||||||
|
|
||||||
|
# validate web tools present
|
||||||
|
[ -d $H/.ros/www ]
|
||||||
|
[ "$(readlink $H/.ros/www/clover)" = "$H/catkin_ws/src/clover/clover/www" ]
|
||||||
|
[ "$(readlink $H/.ros/www/clover_blocks)" = "$H/catkin_ws/src/clover/clover_blocks/www" ]
|
||||||
|
|||||||
@@ -53,7 +53,7 @@ find_package(OpenCV ${_opencv_version} REQUIRED
|
|||||||
## Uncomment this if the package has a setup.py. This macro ensures
|
## Uncomment this if the package has a setup.py. This macro ensures
|
||||||
## modules and global scripts declared therein get installed
|
## modules and global scripts declared therein get installed
|
||||||
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
|
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
|
||||||
# catkin_python_setup()
|
catkin_python_setup()
|
||||||
|
|
||||||
################################################
|
################################################
|
||||||
## Declare ROS messages, services and actions ##
|
## Declare ROS messages, services and actions ##
|
||||||
|
|||||||
64
clover/examples/camera.py
Normal file
64
clover/examples/camera.py
Normal file
@@ -0,0 +1,64 @@
|
|||||||
|
# Information: https://clover.coex.tech/camera
|
||||||
|
|
||||||
|
# Example on basic working with the camera and image processing:
|
||||||
|
|
||||||
|
# - 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.
|
||||||
|
|
||||||
|
import rospy
|
||||||
|
import cv2
|
||||||
|
from sensor_msgs.msg import Image
|
||||||
|
from cv_bridge import CvBridge
|
||||||
|
from clover import long_callback
|
||||||
|
|
||||||
|
rospy.init_node('cv')
|
||||||
|
bridge = CvBridge()
|
||||||
|
|
||||||
|
printed_color = None
|
||||||
|
center_pub = rospy.Publisher('~center', Image, queue_size=1)
|
||||||
|
|
||||||
|
def get_color_name(h):
|
||||||
|
if h < 15: return 'red'
|
||||||
|
elif h < 30: return 'orange'
|
||||||
|
elif h < 60: return 'yellow'
|
||||||
|
elif h < 90: return 'green'
|
||||||
|
elif h < 120: return 'cyan'
|
||||||
|
elif h < 150: return 'blue'
|
||||||
|
elif h < 170: return 'magenta'
|
||||||
|
else: return 'red'
|
||||||
|
|
||||||
|
|
||||||
|
@long_callback
|
||||||
|
def image_callback(msg):
|
||||||
|
img = bridge.imgmsg_to_cv2(msg, 'bgr8')
|
||||||
|
|
||||||
|
# convert to HSV to work with color hue
|
||||||
|
img_hsv = cv2.cvtColor(img, cv2.COLOR_BGR2HSV)
|
||||||
|
|
||||||
|
# cut out a central square
|
||||||
|
w = img.shape[1]
|
||||||
|
h = img.shape[0]
|
||||||
|
r = 20
|
||||||
|
center = img_hsv[h // 2 - r:h // 2 + r, w // 2 - r:w // 2 + r]
|
||||||
|
|
||||||
|
# compute and print the average hue
|
||||||
|
mean_hue = center[:, :, 0].mean()
|
||||||
|
color = get_color_name(mean_hue)
|
||||||
|
global printed_color
|
||||||
|
if color != printed_color:
|
||||||
|
print(color)
|
||||||
|
printed_color = color
|
||||||
|
|
||||||
|
# publish the cropped image
|
||||||
|
center = cv2.cvtColor(center, cv2.COLOR_HSV2BGR)
|
||||||
|
center_pub.publish(bridge.cv2_to_imgmsg(center, 'bgr8'))
|
||||||
|
|
||||||
|
# process every frame:
|
||||||
|
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
|
||||||
|
|
||||||
|
# process 5 frames per second:
|
||||||
|
# image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1)
|
||||||
|
|
||||||
|
rospy.spin()
|
||||||
@@ -18,8 +18,9 @@
|
|||||||
<remap from="map_markers" to="aruco_map/map"/>
|
<remap from="map_markers" to="aruco_map/map"/>
|
||||||
<param name="estimate_poses" value="true"/>
|
<param name="estimate_poses" value="true"/>
|
||||||
<param name="send_tf" value="true"/>
|
<param name="send_tf" value="true"/>
|
||||||
<param name="known_tilt" value="map" if="$(eval placement == 'floor')"/>
|
<param name="use_map_markers" value="true"/>
|
||||||
<param name="known_tilt" value="map_flipped" if="$(eval placement == 'ceiling')"/>
|
<param name="known_vertical" value="map" if="$(eval placement == 'floor' or placement == 'ceiling')"/>
|
||||||
|
<param name="flip_vertical" value="true" if="$(eval placement == 'ceiling')"/>
|
||||||
<param name="length" value="$(arg length)"/>
|
<param name="length" value="$(arg length)"/>
|
||||||
<param name="transform_timeout" value="0.1"/>
|
<param name="transform_timeout" value="0.1"/>
|
||||||
<!-- aruco detector parameters -->
|
<!-- aruco detector parameters -->
|
||||||
@@ -35,8 +36,8 @@
|
|||||||
<remap from="camera_info" to="main_camera/camera_info"/>
|
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||||
<remap from="markers" to="aruco_detect/markers"/>
|
<remap from="markers" to="aruco_detect/markers"/>
|
||||||
<param name="map" value="$(find aruco_pose)/map/$(arg map)"/>
|
<param name="map" value="$(find aruco_pose)/map/$(arg map)"/>
|
||||||
<param name="known_tilt" value="map" if="$(eval placement == 'floor')"/>
|
<param name="known_vertical" value="map" if="$(eval placement == 'floor' or placement == 'ceiling')"/>
|
||||||
<param name="known_tilt" value="map_flipped" if="$(eval placement == 'ceiling')"/>
|
<param name="flip_vertical" value="true" if="$(eval placement == 'ceiling')"/>
|
||||||
<param name="image_axis" value="true"/>
|
<param name="image_axis" value="true"/>
|
||||||
<param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/>
|
<param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/>
|
||||||
<param name="frame_id" value="aruco_map" unless="$(arg aruco_vpe)"/>
|
<param name="frame_id" value="aruco_map" unless="$(arg aruco_vpe)"/>
|
||||||
|
|||||||
@@ -45,10 +45,9 @@
|
|||||||
<remap from="camera_info" to="main_camera/camera_info"/>
|
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||||
<param name="calc_flow_gyro" value="true"/>
|
<param name="calc_flow_gyro" value="true"/>
|
||||||
<param name="roi_rad" value="0.8"/>
|
<param name="roi_rad" value="0.8"/>
|
||||||
|
<param name="disable_on_vpe" value="false"/>
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<node pkg="tf2_ros" type="static_transform_publisher" name="map_flipped_frame" args="0 0 0 3.1415926 3.1415926 0 map map_flipped"/>
|
|
||||||
|
|
||||||
<!-- simplified offboard control -->
|
<!-- simplified offboard control -->
|
||||||
<node name="simple_offboard" pkg="clover" type="simple_offboard" output="screen" clear_params="true">
|
<node name="simple_offboard" pkg="clover" type="simple_offboard" output="screen" clear_params="true">
|
||||||
<param name="reference_frames/main_camera_optical" value="map"/>
|
<param name="reference_frames/main_camera_optical" value="map"/>
|
||||||
@@ -86,8 +85,4 @@
|
|||||||
<param name="use_fake_gcs" value="false"/>
|
<param name="use_fake_gcs" value="false"/>
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<!-- Update static directory -->
|
|
||||||
<node pkg="roswww_static" name="roswww_static" type="main.py" clear_params="true">
|
|
||||||
<param name="default_package" value="clover"/>
|
|
||||||
</node>
|
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -43,8 +43,7 @@
|
|||||||
<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>
|
||||||
<exec_depend>python-pymavlink</exec_depend>
|
<exec_depend>python-pymavlink</exec_depend>
|
||||||
<!-- Use test_depend for packages you need only for testing: -->
|
<test_depend>ros_pytest</test_depend>
|
||||||
<!-- <test_depend>gtest</test_depend> -->
|
|
||||||
|
|
||||||
<!-- The export tag contains other, unspecified, tags -->
|
<!-- The export tag contains other, unspecified, tags -->
|
||||||
<export>
|
<export>
|
||||||
|
|||||||
@@ -1,5 +1,4 @@
|
|||||||
flask==1.1.1
|
flask==1.1.1
|
||||||
docopt==0.6.2
|
|
||||||
geopy==1.11.0
|
geopy==1.11.0
|
||||||
smbus2==0.3.0
|
smbus2==0.3.0
|
||||||
VL53L1X==0.0.5
|
VL53L1X==0.0.5
|
||||||
|
|||||||
11
clover/setup.py
Normal file
11
clover/setup.py
Normal file
@@ -0,0 +1,11 @@
|
|||||||
|
## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD
|
||||||
|
|
||||||
|
from distutils.core import setup
|
||||||
|
from catkin_pkg.python_setup import generate_distutils_setup
|
||||||
|
|
||||||
|
# fetch values from package.xml
|
||||||
|
setup_args = generate_distutils_setup(
|
||||||
|
packages=['clover'],
|
||||||
|
package_dir={'': 'src'})
|
||||||
|
|
||||||
|
setup(**setup_args)
|
||||||
@@ -13,7 +13,12 @@ from util import handle_response
|
|||||||
|
|
||||||
rospy.init_node('autotest_aruco', disable_signals=True) # disable signals to allow interrupting with ctrl+c
|
rospy.init_node('autotest_aruco', disable_signals=True) # disable signals to allow interrupting with ctrl+c
|
||||||
|
|
||||||
flow_client = dynamic_reconfigure.client.Client('optical_flow')
|
try:
|
||||||
|
flow_client = dynamic_reconfigure.client.Client('optical_flow', timeout=2)
|
||||||
|
except rospy.ROSException:
|
||||||
|
flow_client = None
|
||||||
|
print('Cannot configure optical flow, skip')
|
||||||
|
|
||||||
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
||||||
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
|
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
|
||||||
land = handle_response(rospy.ServiceProxy('land', Trigger))
|
land = handle_response(rospy.ServiceProxy('land', Trigger))
|
||||||
@@ -67,12 +72,13 @@ input('Go to center %g %g 1.5 speed 5 [enter] ' % (center_x, center_y))
|
|||||||
navigate_wait(x=center_x, y=center_y, z=1.5, speed=5, frame_id='aruco_map')
|
navigate_wait(x=center_x, y=center_y, z=1.5, speed=5, frame_id='aruco_map')
|
||||||
print_current_map_position()
|
print_current_map_position()
|
||||||
|
|
||||||
input('Disable optical flow and keep hovering [enter] ')
|
if flow_client:
|
||||||
flow_client.update_configuration({'enabled': False})
|
input('Disable optical flow and keep hovering [enter] ')
|
||||||
rospy.sleep(5)
|
flow_client.update_configuration({'enabled': False})
|
||||||
|
rospy.sleep(5)
|
||||||
|
|
||||||
input('Enable optical flow back [enter] ')
|
input('Enable optical flow back [enter] ')
|
||||||
flow_client.update_configuration({'enabled': True})
|
flow_client.update_configuration({'enabled': True})
|
||||||
|
|
||||||
input('Go to side 1 %g 2 heading top [enter] ' % (center_y))
|
input('Go to side 1 %g 2 heading top [enter] ' % (center_y))
|
||||||
navigate_wait(x=1, y=center_y, z=2, yaw=1.57, frame_id='aruco_map')
|
navigate_wait(x=1, y=center_y, z=2, yaw=1.57, frame_id='aruco_map')
|
||||||
|
|||||||
35
clover/src/clover/__init__.py
Normal file
35
clover/src/clover/__init__.py
Normal file
@@ -0,0 +1,35 @@
|
|||||||
|
import rospy
|
||||||
|
from threading import Thread, Event
|
||||||
|
|
||||||
|
def long_callback(fn):
|
||||||
|
"""
|
||||||
|
Decorator fixing a rospy issue for long-running topic callbacks, primarily
|
||||||
|
for image processing.
|
||||||
|
|
||||||
|
See: https://github.com/ros/ros_comm/issues/1901.
|
||||||
|
|
||||||
|
Usage example:
|
||||||
|
|
||||||
|
@long_callback
|
||||||
|
def image_callback(msg):
|
||||||
|
# perform image processing
|
||||||
|
# ...
|
||||||
|
|
||||||
|
rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
|
||||||
|
"""
|
||||||
|
e = Event()
|
||||||
|
|
||||||
|
def thread():
|
||||||
|
while not rospy.is_shutdown():
|
||||||
|
e.wait()
|
||||||
|
e.clear()
|
||||||
|
fn(thread.current_msg)
|
||||||
|
|
||||||
|
thread.current_msg = None
|
||||||
|
Thread(target=thread, daemon=True).start()
|
||||||
|
|
||||||
|
def wrapper(msg):
|
||||||
|
thread.current_msg = msg
|
||||||
|
e.set()
|
||||||
|
|
||||||
|
return wrapper
|
||||||
@@ -319,8 +319,8 @@ int main(int argc, char **argv)
|
|||||||
|
|
||||||
auto set_effect = nh.advertiseService("set_effect", &setEffect);
|
auto set_effect = nh.advertiseService("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);
|
||||||
auto rosout_sub = nh.subscribe("/rosout_agg", 1, &handleLog);
|
auto rosout_sub = nh.subscribe("/rosout_agg", 1, &handleLog);
|
||||||
|
|
||||||
timer = nh.createTimer(ros::Duration(0), &proceed, false, false);
|
timer = nh.createTimer(ros::Duration(0), &proceed, false, false);
|
||||||
|
|||||||
@@ -25,6 +25,7 @@
|
|||||||
#include <dynamic_reconfigure/server.h>
|
#include <dynamic_reconfigure/server.h>
|
||||||
#include <mavros_msgs/OpticalFlowRad.h>
|
#include <mavros_msgs/OpticalFlowRad.h>
|
||||||
#include <sensor_msgs/Imu.h>
|
#include <sensor_msgs/Imu.h>
|
||||||
|
#include <geometry_msgs/PoseStamped.h>
|
||||||
#include <geometry_msgs/Vector3Stamped.h>
|
#include <geometry_msgs/Vector3Stamped.h>
|
||||||
#include <geometry_msgs/PointStamped.h>
|
#include <geometry_msgs/PointStamped.h>
|
||||||
#include <geometry_msgs/TwistStamped.h>
|
#include <geometry_msgs/TwistStamped.h>
|
||||||
@@ -57,6 +58,9 @@ private:
|
|||||||
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
|
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
|
||||||
bool calc_flow_gyro_;
|
bool calc_flow_gyro_;
|
||||||
float flow_gyro_default_;
|
float flow_gyro_default_;
|
||||||
|
bool disable_on_vpe_;
|
||||||
|
ros::Subscriber vpe_sub_;
|
||||||
|
ros::Time last_vpe_time_;
|
||||||
std::shared_ptr<dynamic_reconfigure::Server<clover::FlowConfig>> dyn_srv_;
|
std::shared_ptr<dynamic_reconfigure::Server<clover::FlowConfig>> dyn_srv_;
|
||||||
|
|
||||||
void onInit()
|
void onInit()
|
||||||
@@ -87,6 +91,11 @@ private:
|
|||||||
|
|
||||||
img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this);
|
img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this);
|
||||||
|
|
||||||
|
disable_on_vpe_ = nh_priv.param("disable_on_vpe", false);
|
||||||
|
if (disable_on_vpe_) {
|
||||||
|
vpe_sub_ = nh.subscribe("mavros/vision_pose/pose", 1, &OpticalFlow::vpeCallback, this);
|
||||||
|
}
|
||||||
|
|
||||||
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<clover::FlowConfig>>(nh_priv);
|
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<clover::FlowConfig>>(nh_priv);
|
||||||
dynamic_reconfigure::Server<clover::FlowConfig>::CallbackType cb;
|
dynamic_reconfigure::Server<clover::FlowConfig>::CallbackType cb;
|
||||||
|
|
||||||
@@ -121,6 +130,12 @@ private:
|
|||||||
{
|
{
|
||||||
if (!enabled_) return;
|
if (!enabled_) return;
|
||||||
|
|
||||||
|
if (disable_on_vpe_ &&
|
||||||
|
!last_vpe_time_.isZero() &&
|
||||||
|
(msg->header.stamp - last_vpe_time_).toSec() < 0.1) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
parseCameraInfo(cinfo);
|
parseCameraInfo(cinfo);
|
||||||
|
|
||||||
auto img = cv_bridge::toCvShare(msg, "mono8")->image;
|
auto img = cv_bridge::toCvShare(msg, "mono8")->image;
|
||||||
@@ -236,6 +251,14 @@ private:
|
|||||||
prev_ = curr_.clone();
|
prev_ = curr_.clone();
|
||||||
prev_stamp_ = msg->header.stamp;
|
prev_stamp_ = msg->header.stamp;
|
||||||
|
|
||||||
|
// Publish estimated angular velocity
|
||||||
|
geometry_msgs::TwistStamped velo;
|
||||||
|
velo.header.stamp = msg->header.stamp;
|
||||||
|
velo.header.frame_id = fcu_frame_id_;
|
||||||
|
velo.twist.angular.x = flow_fcu.vector.x / integration_time.toSec();
|
||||||
|
velo.twist.angular.y = flow_fcu.vector.y / integration_time.toSec();
|
||||||
|
velo_pub_.publish(velo);
|
||||||
|
|
||||||
publish_debug:
|
publish_debug:
|
||||||
// Publish debug image
|
// Publish debug image
|
||||||
if (img_pub_.getNumSubscribers() > 0) {
|
if (img_pub_.getNumSubscribers() > 0) {
|
||||||
@@ -248,14 +271,6 @@ publish_debug:
|
|||||||
out_msg.image = img;
|
out_msg.image = img;
|
||||||
img_pub_.publish(out_msg.toImageMsg());
|
img_pub_.publish(out_msg.toImageMsg());
|
||||||
}
|
}
|
||||||
|
|
||||||
// Publish estimated angular velocity
|
|
||||||
geometry_msgs::TwistStamped velo;
|
|
||||||
velo.header.stamp = msg->header.stamp;
|
|
||||||
velo.header.frame_id = fcu_frame_id_;
|
|
||||||
velo.twist.angular.x = flow_fcu.vector.x / integration_time.toSec();
|
|
||||||
velo.twist.angular.y = flow_fcu.vector.y / integration_time.toSec();
|
|
||||||
velo_pub_.publish(velo);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -284,6 +299,10 @@ publish_debug:
|
|||||||
prev_ = Mat(); // clear previous frame
|
prev_ = Mat(); // clear previous frame
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void vpeCallback(const geometry_msgs::PoseStamped& vpe) {
|
||||||
|
last_vpe_time_ = vpe.header.stamp;
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
PLUGINLIB_EXPORT_CLASS(OpticalFlow, nodelet::Nodelet)
|
PLUGINLIB_EXPORT_CLASS(OpticalFlow, nodelet::Nodelet)
|
||||||
|
|||||||
@@ -9,13 +9,14 @@
|
|||||||
# The above copyright notice and this permission notice shall be included in all
|
# The above copyright notice and this permission notice shall be included in all
|
||||||
# copies or substantial portions of the Software.
|
# copies or substantial portions of the Software.
|
||||||
|
|
||||||
import os
|
import os, sys
|
||||||
import math
|
import math
|
||||||
import subprocess
|
import subprocess
|
||||||
import re
|
import re
|
||||||
from collections import OrderedDict
|
from collections import OrderedDict
|
||||||
import traceback
|
import traceback
|
||||||
from threading import Event
|
import threading
|
||||||
|
from threading import Event, Thread, Lock
|
||||||
import numpy
|
import numpy
|
||||||
import rospy
|
import rospy
|
||||||
import tf2_ros
|
import tf2_ros
|
||||||
@@ -27,24 +28,16 @@ from mavros_msgs.msg import State, OpticalFlowRad, Mavlink
|
|||||||
from mavros_msgs.srv import ParamGet
|
from mavros_msgs.srv import ParamGet
|
||||||
from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped, Vector3Stamped
|
from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped, Vector3Stamped
|
||||||
from visualization_msgs.msg import MarkerArray as VisualizationMarkerArray
|
from visualization_msgs.msg import MarkerArray as VisualizationMarkerArray
|
||||||
|
from diagnostic_msgs.msg import DiagnosticArray
|
||||||
import tf.transformations as t
|
import tf.transformations as t
|
||||||
from aruco_pose.msg import MarkerArray
|
from aruco_pose.msg import MarkerArray
|
||||||
from mavros import mavlink
|
from mavros import mavlink
|
||||||
import locale
|
import locale
|
||||||
|
|
||||||
|
|
||||||
# TODO: check attitude is present
|
|
||||||
# TODO: disk free space
|
|
||||||
# TODO: map, base_link, body
|
|
||||||
# TODO: rc service
|
|
||||||
# TODO: perform commander check, ekf2 status on PX4
|
|
||||||
# TODO: check if FCU params setter succeed
|
|
||||||
# TODO: selfcheck ROS service (with blacklists for checks)
|
|
||||||
|
|
||||||
|
|
||||||
rospy.init_node('selfcheck')
|
rospy.init_node('selfcheck')
|
||||||
|
|
||||||
os.environ['ROSCONSOLE_FORMAT']='[${severity}]: ${message}'
|
os.environ['ROSCONSOLE_FORMAT']='${message}'
|
||||||
|
|
||||||
# use user's locale to convert numbers, etc
|
# use user's locale to convert numbers, etc
|
||||||
locale.setlocale(locale.LC_ALL, '')
|
locale.setlocale(locale.LC_ALL, '')
|
||||||
@@ -53,46 +46,68 @@ tf_buffer = tf2_ros.Buffer()
|
|||||||
tf_listener = tf2_ros.TransformListener(tf_buffer)
|
tf_listener = tf2_ros.TransformListener(tf_buffer)
|
||||||
|
|
||||||
|
|
||||||
failures = []
|
thread_local = threading.local()
|
||||||
infos = []
|
reports_lock = Lock()
|
||||||
current_check = None
|
|
||||||
|
|
||||||
|
# formatting colors
|
||||||
|
if sys.stdout.isatty():
|
||||||
|
GREY = '\033[90m'
|
||||||
|
GREEN = '\033[92m'
|
||||||
|
RED = '\033[31m'
|
||||||
|
END = '\033[0m'
|
||||||
|
else:
|
||||||
|
GREY = GREEN = RED = END = ''
|
||||||
|
|
||||||
|
|
||||||
def failure(text, *args):
|
def failure(text, *args):
|
||||||
msg = text % args
|
msg = text % args
|
||||||
rospy.logwarn('%s: %s', current_check, msg)
|
thread_local.reports += [{'failure': msg}]
|
||||||
failures.append(msg)
|
|
||||||
|
|
||||||
|
|
||||||
def info(text, *args):
|
def info(text, *args):
|
||||||
msg = text % args
|
msg = text % args
|
||||||
rospy.loginfo('%s: %s', current_check, msg)
|
thread_local.reports += [{'info': msg}]
|
||||||
infos.append(msg)
|
|
||||||
|
|
||||||
|
|
||||||
def check(name):
|
def check(name):
|
||||||
def inner(fn):
|
def inner(fn):
|
||||||
def wrapper(*args, **kwargs):
|
def wrapper(*args, **kwargs):
|
||||||
failures[:] = []
|
start = rospy.get_time()
|
||||||
infos[:] = []
|
thread_local.reports = []
|
||||||
global current_check
|
|
||||||
current_check = name
|
|
||||||
try:
|
try:
|
||||||
fn(*args, **kwargs)
|
fn(*args, **kwargs)
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
traceback.print_exc()
|
traceback.print_exc()
|
||||||
rospy.logerr('%s: exception occurred', name)
|
rospy.logerr('%s: exception occurred', name)
|
||||||
return
|
with reports_lock:
|
||||||
if not failures and not infos:
|
for report in thread_local.reports:
|
||||||
rospy.loginfo('%s: OK', name)
|
if 'failure' in report:
|
||||||
|
rospy.logerr('%s: %s', name, report['failure'])
|
||||||
|
elif 'info' in report:
|
||||||
|
rospy.loginfo(GREY + name + END + ': ' + report['info'])
|
||||||
|
if not thread_local.reports:
|
||||||
|
rospy.loginfo(GREY + name + END + ': ' + GREEN + 'OK' + END)
|
||||||
|
if rospy.get_param('~time', False):
|
||||||
|
rospy.loginfo('%s: %.1f sec', name, rospy.get_time() - start)
|
||||||
return wrapper
|
return wrapper
|
||||||
return inner
|
return inner
|
||||||
|
|
||||||
|
|
||||||
|
def ff(value, precision=2):
|
||||||
|
# safely format float or int
|
||||||
|
if value is None:
|
||||||
|
return RED + '???' + END
|
||||||
|
if isinstance(value, float):
|
||||||
|
return ('{:.' + str(precision + 1) + '}').format(value)
|
||||||
|
elif isinstance(value, int):
|
||||||
|
return str(value)
|
||||||
|
|
||||||
|
|
||||||
param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
|
param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
|
||||||
|
|
||||||
|
|
||||||
def get_param(name):
|
def get_param(name, default=None):
|
||||||
try:
|
try:
|
||||||
res = param_get(param_id=name)
|
res = param_get(param_id=name)
|
||||||
except rospy.ServiceException as e:
|
except rospy.ServiceException as e:
|
||||||
@@ -101,12 +116,17 @@ def get_param(name):
|
|||||||
|
|
||||||
if not res.success:
|
if not res.success:
|
||||||
failure('unable to retrieve PX4 parameter %s', name)
|
failure('unable to retrieve PX4 parameter %s', name)
|
||||||
|
return default
|
||||||
else:
|
else:
|
||||||
if res.value.integer != 0:
|
if res.value.integer != 0:
|
||||||
return res.value.integer
|
return res.value.integer
|
||||||
return res.value.real
|
return res.value.real
|
||||||
|
|
||||||
|
|
||||||
|
def get_paramf(name, precision=2):
|
||||||
|
return ff(get_param(name), precision)
|
||||||
|
|
||||||
|
|
||||||
recv_event = Event()
|
recv_event = Event()
|
||||||
link = mavutil.mavlink.MAVLink('', 255, 1)
|
link = mavutil.mavlink.MAVLink('', 255, 1)
|
||||||
mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
|
mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
|
||||||
@@ -151,6 +171,24 @@ def mavlink_exec(cmd, timeout=3.0):
|
|||||||
return mavlink_recv
|
return mavlink_recv
|
||||||
|
|
||||||
|
|
||||||
|
def read_diagnostics(name, key):
|
||||||
|
e = Event()
|
||||||
|
def cb(msg):
|
||||||
|
for status in msg.status:
|
||||||
|
if status.name.lower() == name.lower():
|
||||||
|
for value in status.values:
|
||||||
|
if value.key.lower() == key.lower():
|
||||||
|
cb.value = value.value
|
||||||
|
e.set()
|
||||||
|
return
|
||||||
|
|
||||||
|
cb.value = None
|
||||||
|
sub = rospy.Subscriber('/diagnostics', DiagnosticArray, cb)
|
||||||
|
e.wait(1.0) # wait to read all the diagnostics from nodes publishing them
|
||||||
|
sub.unregister()
|
||||||
|
return cb.value
|
||||||
|
|
||||||
|
|
||||||
BOARD_ROTATIONS = {
|
BOARD_ROTATIONS = {
|
||||||
0: 'no rotation',
|
0: 'no rotation',
|
||||||
1: 'yaw 45°',
|
1: 'yaw 45°',
|
||||||
@@ -196,29 +234,31 @@ def check_fcu():
|
|||||||
state = rospy.wait_for_message('mavros/state', State, timeout=3)
|
state = rospy.wait_for_message('mavros/state', State, timeout=3)
|
||||||
if not state.connected:
|
if not state.connected:
|
||||||
failure('no connection to the FCU (check wiring)')
|
failure('no connection to the FCU (check wiring)')
|
||||||
|
info('fcu_url = %s', rospy.get_param('mavros/fcu_url', '?'))
|
||||||
return
|
return
|
||||||
|
|
||||||
clover_tag = re.compile(r'-cl[oe]ver\.\d+$')
|
if not is_process_running('px4', exact=True): # can't use px4 console in SITL
|
||||||
clover_fw = False
|
clover_tag = re.compile(r'-cl[oe]ver\.\d+$')
|
||||||
|
clover_fw = False
|
||||||
|
|
||||||
# Make sure the console is available to us
|
# Make sure the console is available to us
|
||||||
mavlink_exec('\n')
|
mavlink_exec('\n')
|
||||||
version_str = mavlink_exec('ver all')
|
version_str = mavlink_exec('ver all')
|
||||||
if version_str == '':
|
if version_str == '':
|
||||||
info('no version data available from SITL')
|
info('no version data available from SITL')
|
||||||
|
|
||||||
for line in version_str.split('\n'):
|
for line in version_str.split('\n'):
|
||||||
if line.startswith('FW version: '):
|
if line.startswith('FW version: '):
|
||||||
info(line[len('FW version: '):])
|
info(line[len('FW version: '):])
|
||||||
elif line.startswith('FW git tag: '): # only Clover's firmware
|
elif line.startswith('FW git tag: '): # only Clover's firmware
|
||||||
tag = line[len('FW git tag: '):]
|
tag = line[len('FW git tag: '):]
|
||||||
clover_fw = clover_tag.search(tag)
|
clover_fw = clover_tag.search(tag)
|
||||||
info(tag)
|
info(tag)
|
||||||
elif line.startswith('HW arch: '):
|
elif line.startswith('HW arch: '):
|
||||||
info(line[len('HW arch: '):])
|
info(line[len('HW arch: '):])
|
||||||
|
|
||||||
if not clover_fw:
|
if not clover_fw:
|
||||||
info('not Clover PX4 firmware, check https://clover.coex.tech/firmware')
|
info('not Clover PX4 firmware, check https://clover.coex.tech/firmware')
|
||||||
|
|
||||||
est = get_param('SYS_MC_EST_GROUP')
|
est = get_param('SYS_MC_EST_GROUP')
|
||||||
if est == 1:
|
if est == 1:
|
||||||
@@ -255,21 +295,29 @@ def check_fcu():
|
|||||||
if cbrk_usb_chk != 197848:
|
if cbrk_usb_chk != 197848:
|
||||||
failure('set parameter CBRK_USB_CHK to 197848 for flying with USB connected')
|
failure('set parameter CBRK_USB_CHK to 197848 for flying with USB connected')
|
||||||
|
|
||||||
|
if not is_process_running('px4', exact=True): # skip battery check in SITL
|
||||||
|
try:
|
||||||
|
battery = rospy.wait_for_message('mavros/battery', BatteryState, timeout=3)
|
||||||
|
if not battery.cell_voltage:
|
||||||
|
failure('cell voltage is not available, https://clover.coex.tech/power')
|
||||||
|
else:
|
||||||
|
cell = battery.cell_voltage[0]
|
||||||
|
if cell > 4.3 or cell < 3.0:
|
||||||
|
failure('incorrect cell voltage: %.2f V, https://clover.coex.tech/power', cell)
|
||||||
|
elif cell < 3.7:
|
||||||
|
failure('critically low cell voltage: %.2f V, recharge battery', cell)
|
||||||
|
except rospy.ROSException:
|
||||||
|
failure('no battery state')
|
||||||
|
|
||||||
|
# time sync check
|
||||||
try:
|
try:
|
||||||
battery = rospy.wait_for_message('mavros/battery', BatteryState, timeout=3)
|
info('time sync offset: %.2f s', float(read_diagnostics('mavros: Time Sync', 'Estimated time offset (s)')))
|
||||||
if not battery.cell_voltage:
|
except:
|
||||||
failure('cell voltage is not available, https://clover.coex.tech/power')
|
failure('cannot read time sync offset')
|
||||||
else:
|
|
||||||
cell = battery.cell_voltage[0]
|
|
||||||
if cell > 4.3 or cell < 3.0:
|
|
||||||
failure('incorrect cell voltage: %.2f V, https://clover.coex.tech/power', cell)
|
|
||||||
elif cell < 3.7:
|
|
||||||
failure('critically low cell voltage: %.2f V, recharge battery', cell)
|
|
||||||
except rospy.ROSException:
|
|
||||||
failure('no battery state')
|
|
||||||
|
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
failure('no MAVROS state (check wiring)')
|
failure('no MAVROS state (check wiring)')
|
||||||
|
info('fcu_url = %s', rospy.get_param('mavros/fcu_url', '?'))
|
||||||
|
|
||||||
|
|
||||||
def describe_direction(v):
|
def describe_direction(v):
|
||||||
@@ -346,19 +394,24 @@ def is_process_running(binary, exact=False, full=False):
|
|||||||
|
|
||||||
@check('ArUco markers')
|
@check('ArUco markers')
|
||||||
def check_aruco():
|
def check_aruco():
|
||||||
|
markers = None
|
||||||
|
|
||||||
if is_process_running('aruco_detect', full=True):
|
if is_process_running('aruco_detect', full=True):
|
||||||
try:
|
try:
|
||||||
info('aruco_detect/length = %g m', rospy.get_param('aruco_detect/length'))
|
info('aruco_detect/length = %g m', rospy.get_param('aruco_detect/length', '?'))
|
||||||
except KeyError:
|
except KeyError:
|
||||||
failure('aruco_detect/length parameter is not set')
|
failure('aruco_detect/length parameter is not set')
|
||||||
known_tilt = rospy.get_param('aruco_detect/known_tilt', '')
|
known_vertical = rospy.get_param('aruco_detect/known_vertical', '')
|
||||||
if known_tilt == 'map':
|
flip_vertical = rospy.get_param('aruco_detect/flip_vertical', False)
|
||||||
known_tilt += ' (ALL markers are on the floor)'
|
description = ''
|
||||||
elif known_tilt == 'map_flipped':
|
if known_vertical == 'map' and not flip_vertical:
|
||||||
known_tilt += ' (ALL markers are on the ceiling)'
|
description = ' (all markers are on the floor)'
|
||||||
info('aruco_detector/known_tilt = %s', known_tilt)
|
elif known_vertical == 'map' and flip_vertical:
|
||||||
|
description = ' (all markers are on the ceiling)'
|
||||||
|
info('aruco_detect/known_vertical = %s', known_vertical)
|
||||||
|
info('aruco_detect/flip_vertical = %s%s', flip_vertical, description)
|
||||||
try:
|
try:
|
||||||
rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=1)
|
markers = rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=0.8)
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
failure('no markers detection')
|
failure('no markers detection')
|
||||||
return
|
return
|
||||||
@@ -367,42 +420,61 @@ def check_aruco():
|
|||||||
return
|
return
|
||||||
|
|
||||||
if is_process_running('aruco_map', full=True):
|
if is_process_running('aruco_map', full=True):
|
||||||
known_tilt = rospy.get_param('aruco_map/known_tilt', '')
|
known_vertical = rospy.get_param('aruco_map/known_vertical', '')
|
||||||
if known_tilt == 'map':
|
flip_vertical = rospy.get_param('aruco_map/flip_vertical', False)
|
||||||
known_tilt += ' (marker\'s map is on the floor)'
|
description = ''
|
||||||
elif known_tilt == 'map_flipped':
|
if known_vertical == 'map' and not flip_vertical:
|
||||||
known_tilt += ' (marker\'s map is on the ceiling)'
|
description += ' (markers map is on the floor)'
|
||||||
info('aruco_map/known_tilt = %s', known_tilt)
|
elif known_vertical == 'map' and flip_vertical:
|
||||||
|
description += ' (markers map is on the ceiling)'
|
||||||
|
info('aruco_map/known_vertical = %s', known_vertical)
|
||||||
|
info('aruco_map/flip_vertical = %s%s', flip_vertical, description)
|
||||||
|
|
||||||
try:
|
try:
|
||||||
visualization = rospy.wait_for_message('aruco_map/visualization', VisualizationMarkerArray, timeout=1)
|
visualization = rospy.wait_for_message('aruco_map/visualization', VisualizationMarkerArray, timeout=0.8)
|
||||||
info('map has %s markers', len(visualization.markers))
|
info('map has %s markers', len(visualization.markers))
|
||||||
except:
|
except:
|
||||||
failure('cannot read aruco_map/visualization topic')
|
failure('cannot read aruco_map/visualization topic')
|
||||||
|
|
||||||
try:
|
try:
|
||||||
rospy.wait_for_message('aruco_map/pose', PoseWithCovarianceStamped, timeout=1)
|
rospy.wait_for_message('aruco_map/pose', PoseWithCovarianceStamped, timeout=0.8)
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
failure('no map detection')
|
if not markers:
|
||||||
|
info('no map detection as no markers detection')
|
||||||
|
elif not markers.markers:
|
||||||
|
info('no map detection as no markers detected')
|
||||||
|
else:
|
||||||
|
failure('no map detection')
|
||||||
else:
|
else:
|
||||||
info('aruco_map is not running')
|
info('aruco_map is not running')
|
||||||
|
|
||||||
|
|
||||||
|
def is_on_the_floor():
|
||||||
|
try:
|
||||||
|
dist = rospy.wait_for_message('rangefinder/range', Range, timeout=1)
|
||||||
|
return dist.range < 0.3
|
||||||
|
except rospy.ROSException:
|
||||||
|
return False
|
||||||
|
|
||||||
|
|
||||||
@check('Vision position estimate')
|
@check('Vision position estimate')
|
||||||
def check_vpe():
|
def check_vpe():
|
||||||
vis = None
|
vis = None
|
||||||
try:
|
try:
|
||||||
vis = rospy.wait_for_message('mavros/vision_pose/pose', PoseStamped, timeout=1)
|
vis = rospy.wait_for_message('mavros/vision_pose/pose', PoseStamped, timeout=0.8)
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
try:
|
try:
|
||||||
vis = rospy.wait_for_message('mavros/mocap/pose', PoseStamped, timeout=1)
|
vis = rospy.wait_for_message('mavros/mocap/pose', PoseStamped, timeout=0.8)
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
failure('no VPE or MoCap messages')
|
if not is_process_running('vpe_publisher', full=True):
|
||||||
# check if vpe_publisher is running
|
info('no vision position estimate, vpe_publisher is not running')
|
||||||
try:
|
elif rospy.get_param('aruco_map/known_vertical', '') == 'map' \
|
||||||
subprocess.check_output(['pgrep', '-x', 'vpe_publisher'])
|
and rospy.get_param('aruco_map/flip_vertical', False):
|
||||||
except subprocess.CalledProcessError:
|
failure('no vision position estimate, markers are on the ceiling')
|
||||||
return # it's not running, skip following checks
|
elif is_on_the_floor():
|
||||||
|
info('no vision position estimate, the drone is on the floor')
|
||||||
|
else:
|
||||||
|
failure('no vision position estimate')
|
||||||
|
|
||||||
# check PX4 settings
|
# check PX4 settings
|
||||||
est = get_param('SYS_MC_EST_GROUP')
|
est = get_param('SYS_MC_EST_GROUP')
|
||||||
@@ -414,14 +486,14 @@ def check_vpe():
|
|||||||
if vision_yaw_w == 0:
|
if vision_yaw_w == 0:
|
||||||
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: %.2f', vision_yaw_w)
|
info('vision yaw weight: %s', ff(vision_yaw_w))
|
||||||
fuse = get_param('LPE_FUSION')
|
fuse = 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')
|
||||||
if delay != 0:
|
if delay != 0:
|
||||||
failure('LPE_VIS_DELAY parameter is %s, but it should be zero', delay)
|
failure('LPE_VIS_DELAY = %s, but it should be zero', delay)
|
||||||
info('LPE_VIS_XY is %.2f m, LPE_VIS_Z is %.2f m', get_param('LPE_VIS_XY'), get_param('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')
|
fuse = get_param('EKF2_AID_MASK')
|
||||||
if not fuse & (1 << 3):
|
if not fuse & (1 << 3):
|
||||||
@@ -430,10 +502,10 @@ def check_vpe():
|
|||||||
failure('vision yaw fusion is disabled, change EKF2_AID_MASK parameter')
|
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 is %.2f, but it should be zero', delay)
|
failure('EKF2_EV_DELAY = %.2f, but it should be zero', delay)
|
||||||
info('EKF2_EVA_NOISE is %.3f, EKF2_EVP_NOISE is %.3f',
|
info('EKF2_EVA_NOISE = %s, EKF2_EVP_NOISE = %s',
|
||||||
get_param('EKF2_EVA_NOISE'),
|
get_paramf('EKF2_EVA_NOISE', 3),
|
||||||
get_param('EKF2_EVP_NOISE'))
|
get_paramf('EKF2_EVP_NOISE', 3))
|
||||||
|
|
||||||
if not vis:
|
if not vis:
|
||||||
return
|
return
|
||||||
@@ -531,15 +603,19 @@ def check_velocity():
|
|||||||
@check('Global position (GPS)')
|
@check('Global position (GPS)')
|
||||||
def check_global_position():
|
def check_global_position():
|
||||||
try:
|
try:
|
||||||
rospy.wait_for_message('mavros/global_position/global', NavSatFix, timeout=1)
|
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') & (1 << 0)):
|
if get_param('SYS_MC_EST_GROUP') == 2 and (get_param('EKF2_AID_MASK', 0) & (1 << 0)):
|
||||||
failure('enabled GPS fusion may suppress vision position aiding')
|
failure('enabled GPS fusion may suppress vision position aiding')
|
||||||
|
|
||||||
|
|
||||||
@check('Optical flow')
|
@check('Optical flow')
|
||||||
def check_optical_flow():
|
def check_optical_flow():
|
||||||
|
if not is_process_running('optical_flow', full=True):
|
||||||
|
info('optical_flow is not running')
|
||||||
|
return
|
||||||
|
|
||||||
# TODO:check FPS!
|
# TODO:check FPS!
|
||||||
try:
|
try:
|
||||||
rospy.wait_for_message('mavros/px4flow/raw/send', OpticalFlowRad, timeout=0.5)
|
rospy.wait_for_message('mavros/px4flow/raw/send', OpticalFlowRad, timeout=0.5)
|
||||||
@@ -547,7 +623,7 @@ def check_optical_flow():
|
|||||||
# check PX4 settings
|
# check PX4 settings
|
||||||
rot = get_param('SENS_FLOW_ROT')
|
rot = get_param('SENS_FLOW_ROT')
|
||||||
if rot != 0:
|
if rot != 0:
|
||||||
failure('SENS_FLOW_ROT parameter is %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 = get_param('LPE_FUSION')
|
||||||
@@ -555,32 +631,36 @@ def check_optical_flow():
|
|||||||
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):
|
||||||
failure('flow gyro compensation is disabled, change LPE_FUSION parameter')
|
failure('flow gyro compensation is disabled, change LPE_FUSION parameter')
|
||||||
scale = get_param('LPE_FLW_SCALE')
|
scale = get_param('LPE_FLW_SCALE', 1)
|
||||||
if not numpy.isclose(scale, 1.0):
|
if not numpy.isclose(scale, 1.0):
|
||||||
failure('LPE_FLW_SCALE parameter is %.2f, but it should be 1.0', scale)
|
failure('LPE_FLW_SCALE = %.2f, but it should be 1.0', scale)
|
||||||
|
|
||||||
info('LPE_FLW_QMIN is %s, LPE_FLW_R is %.4f, LPE_FLW_RR is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
|
info('LPE_FLW_QMIN = %s, LPE_FLW_R = %s, LPE_FLW_RR = %s',
|
||||||
get_param('LPE_FLW_QMIN'),
|
get_paramf('LPE_FLW_QMIN'),
|
||||||
get_param('LPE_FLW_R'),
|
get_paramf('LPE_FLW_R', 4),
|
||||||
get_param('LPE_FLW_RR'),
|
get_paramf('LPE_FLW_RR', 4))
|
||||||
get_param('SENS_FLOW_MINHGT'),
|
|
||||||
get_param('SENS_FLOW_MAXHGT'))
|
|
||||||
elif est == 2:
|
elif est == 2:
|
||||||
fuse = get_param('EKF2_AID_MASK')
|
fuse = get_param('EKF2_AID_MASK', 0)
|
||||||
if not fuse & (1 << 1):
|
if not fuse & (1 << 1):
|
||||||
failure('optical flow fusion is disabled, change EKF2_AID_MASK parameter')
|
failure('optical flow fusion is disabled, change EKF2_AID_MASK parameter')
|
||||||
delay = get_param('EKF2_OF_DELAY')
|
delay = get_param('EKF2_OF_DELAY', 0)
|
||||||
if delay != 0:
|
if delay != 0:
|
||||||
failure('EKF2_OF_DELAY is %.2f, but it should be zero', delay)
|
failure('EKF2_OF_DELAY = %.2f, but it should be zero', delay)
|
||||||
info('EKF2_OF_QMIN is %s, EKF2_OF_N_MIN is %.4f, EKF2_OF_N_MAX is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
|
info('EKF2_OF_QMIN = %s, EKF2_OF_N_MIN = %s, EKF2_OF_N_MAX = %s',
|
||||||
get_param('EKF2_OF_QMIN'),
|
get_paramf('EKF2_OF_QMIN'),
|
||||||
get_param('EKF2_OF_N_MIN'),
|
get_paramf('EKF2_OF_N_MIN', 4),
|
||||||
get_param('EKF2_OF_N_MAX'),
|
get_paramf('EKF2_OF_N_MAX', 4))
|
||||||
get_param('SENS_FLOW_MINHGT'),
|
info('SENS_FLOW_MINHGT = %s, SENS_FLOW_MAXHGT = %s', get_paramf('SENS_FLOW_MINHGT', 3), get_paramf('SENS_FLOW_MAXHGT', 3))
|
||||||
get_param('SENS_FLOW_MAXHGT'))
|
|
||||||
|
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
failure('no optical flow data (from Raspberry)')
|
if rospy.get_param('optical_flow/disable_on_vpe', False):
|
||||||
|
try:
|
||||||
|
rospy.wait_for_message('mavros/vision_pose/pose', PoseStamped, timeout=1)
|
||||||
|
info('no optical flow as disable_on_vpe is true')
|
||||||
|
except:
|
||||||
|
failure('no optical flow on RPi, disable_on_vpe is true, but no vision pose also')
|
||||||
|
else:
|
||||||
|
failure('no optical flow on RPi')
|
||||||
|
|
||||||
|
|
||||||
@check('Rangefinder')
|
@check('Rangefinder')
|
||||||
@@ -604,7 +684,7 @@ 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')
|
fuse = 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:
|
||||||
@@ -638,7 +718,7 @@ def check_boot_duration():
|
|||||||
|
|
||||||
@check('CPU usage')
|
@check('CPU usage')
|
||||||
def check_cpu_usage():
|
def check_cpu_usage():
|
||||||
WHITELIST = 'nodelet', 'gzclient', 'gzserver'
|
WHITELIST = 'nodelet', 'gzclient', 'gzserver', 'selfcheck.py'
|
||||||
CMD = "top -n 1 -b -i | tail -n +8 | awk '{ printf(\"%-8s\\t%-8s\\t%-8s\\n\", $1, $9, $12); }'"
|
CMD = "top -n 1 -b -i | tail -n +8 | awk '{ printf(\"%-8s\\t%-8s\\t%-8s\\n\", $1, $9, $12); }'"
|
||||||
output = subprocess.check_output(CMD, shell=True).decode()
|
output = subprocess.check_output(CMD, shell=True).decode()
|
||||||
processes = output.split('\n')
|
processes = output.split('\n')
|
||||||
@@ -707,7 +787,10 @@ def check_image():
|
|||||||
try:
|
try:
|
||||||
info('version: %s', open('/etc/clover_version').read().strip())
|
info('version: %s', open('/etc/clover_version').read().strip())
|
||||||
except IOError:
|
except IOError:
|
||||||
info('no /etc/clover_version file, not the Clover image?')
|
try:
|
||||||
|
info('VM version: %s', open('/etc/clover_vm_version').read().strip())
|
||||||
|
except IOError:
|
||||||
|
info('no /etc/clover_version file, not the Clover image?')
|
||||||
|
|
||||||
|
|
||||||
@check('Preflight status')
|
@check('Preflight status')
|
||||||
@@ -818,26 +901,47 @@ def check_board():
|
|||||||
info('could not open /proc/device-tree/model, not a Raspberry Pi?')
|
info('could not open /proc/device-tree/model, not a Raspberry Pi?')
|
||||||
|
|
||||||
|
|
||||||
|
def parallel_for(fns):
|
||||||
|
threads = []
|
||||||
|
for fn in fns:
|
||||||
|
thread = Thread(target=fn)
|
||||||
|
thread.start()
|
||||||
|
threads.append(thread)
|
||||||
|
for thread in threads:
|
||||||
|
thread.join()
|
||||||
|
|
||||||
|
|
||||||
|
def consequentially_for(fns):
|
||||||
|
for fn in fns:
|
||||||
|
fn()
|
||||||
|
|
||||||
|
|
||||||
def selfcheck():
|
def selfcheck():
|
||||||
check_image()
|
checks = [
|
||||||
check_board()
|
check_image,
|
||||||
check_clover_service()
|
check_board,
|
||||||
check_network()
|
check_clover_service,
|
||||||
check_fcu()
|
check_network,
|
||||||
check_imu()
|
check_fcu,
|
||||||
check_local_position()
|
check_imu,
|
||||||
check_velocity()
|
check_local_position,
|
||||||
check_global_position()
|
check_velocity,
|
||||||
check_preflight_status()
|
check_global_position,
|
||||||
check_main_camera()
|
check_preflight_status,
|
||||||
check_aruco()
|
check_main_camera,
|
||||||
check_simpleoffboard()
|
check_aruco,
|
||||||
check_optical_flow()
|
check_simpleoffboard,
|
||||||
check_vpe()
|
check_optical_flow,
|
||||||
check_rangefinder()
|
check_vpe,
|
||||||
check_rpi_health()
|
check_rangefinder,
|
||||||
check_cpu_usage()
|
check_rpi_health,
|
||||||
check_boot_duration()
|
check_cpu_usage,
|
||||||
|
check_boot_duration,
|
||||||
|
]
|
||||||
|
if rospy.get_param('~parallel', False):
|
||||||
|
parallel_for(checks)
|
||||||
|
else:
|
||||||
|
consequentially_for(checks)
|
||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
|
|||||||
@@ -37,7 +37,6 @@
|
|||||||
#include <mavros_msgs/State.h>
|
#include <mavros_msgs/State.h>
|
||||||
#include <mavros_msgs/StatusText.h>
|
#include <mavros_msgs/StatusText.h>
|
||||||
#include <mavros_msgs/ManualControl.h>
|
#include <mavros_msgs/ManualControl.h>
|
||||||
#include <mavros_msgs/Altitude.h>
|
|
||||||
|
|
||||||
#include <clover/GetTelemetry.h>
|
#include <clover/GetTelemetry.h>
|
||||||
#include <clover/Navigate.h>
|
#include <clover/Navigate.h>
|
||||||
@@ -55,7 +54,6 @@ using namespace clover;
|
|||||||
using mavros_msgs::PositionTarget;
|
using mavros_msgs::PositionTarget;
|
||||||
using mavros_msgs::AttitudeTarget;
|
using mavros_msgs::AttitudeTarget;
|
||||||
using mavros_msgs::Thrust;
|
using mavros_msgs::Thrust;
|
||||||
using mavros_msgs::Altitude;
|
|
||||||
|
|
||||||
// tf2
|
// tf2
|
||||||
tf2_ros::Buffer tf_buffer;
|
tf2_ros::Buffer tf_buffer;
|
||||||
@@ -98,12 +96,10 @@ Thrust thrust_msg;
|
|||||||
TwistStamped rates_msg;
|
TwistStamped rates_msg;
|
||||||
TransformStamped target, setpoint;
|
TransformStamped target, setpoint;
|
||||||
geometry_msgs::TransformStamped body;
|
geometry_msgs::TransformStamped body;
|
||||||
geometry_msgs::TransformStamped terrain;
|
|
||||||
|
|
||||||
// State
|
// State
|
||||||
PoseStamped nav_start;
|
PoseStamped nav_start;
|
||||||
PoseStamped setpoint_position, setpoint_position_transformed;
|
PoseStamped setpoint_position, setpoint_position_transformed;
|
||||||
Vector3Stamped setpoint_z, setpoint_z_transformed; // for z-only commands
|
|
||||||
Vector3Stamped setpoint_velocity, setpoint_velocity_transformed;
|
Vector3Stamped setpoint_velocity, setpoint_velocity_transformed;
|
||||||
QuaternionStamped setpoint_attitude, setpoint_attitude_transformed;
|
QuaternionStamped setpoint_attitude, setpoint_attitude_transformed;
|
||||||
float setpoint_yaw_rate;
|
float setpoint_yaw_rate;
|
||||||
@@ -126,8 +122,6 @@ enum setpoint_type_t setpoint_type = NONE;
|
|||||||
|
|
||||||
enum { YAW, YAW_RATE, TOWARDS } setpoint_yaw_type;
|
enum { YAW, YAW_RATE, TOWARDS } setpoint_yaw_type;
|
||||||
|
|
||||||
bool setpoint_z_valid = false;
|
|
||||||
|
|
||||||
// Last received telemetry messages
|
// Last received telemetry messages
|
||||||
mavros_msgs::State state;
|
mavros_msgs::State state;
|
||||||
mavros_msgs::StatusText statustext;
|
mavros_msgs::StatusText statustext;
|
||||||
@@ -179,15 +173,6 @@ void handleLocalPosition(const PoseStamped& pose)
|
|||||||
// TODO: terrain?, home?
|
// TODO: terrain?, home?
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleAltitude(const Altitude& alt)
|
|
||||||
{
|
|
||||||
// publish terrain frame
|
|
||||||
if (!std::isfinite(alt.bottom_clearance)) return;
|
|
||||||
terrain.header.stamp = alt.header.stamp;
|
|
||||||
terrain.transform.translation.z = -alt.bottom_clearance;
|
|
||||||
transform_broadcaster->sendTransform(terrain);
|
|
||||||
}
|
|
||||||
|
|
||||||
// wait for transform without interrupting publishing setpoints
|
// wait for transform without interrupting publishing setpoints
|
||||||
inline bool waitTransform(const string& target, const string& source,
|
inline bool waitTransform(const string& target, const string& source,
|
||||||
const ros::Time& stamp, const ros::Duration& timeout) // editorconfig-checker-disable-line
|
const ros::Time& stamp, const ros::Duration& timeout) // editorconfig-checker-disable-line
|
||||||
@@ -436,18 +421,6 @@ void publish(const ros::Time stamp)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (setpoint_z_valid && setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
|
|
||||||
setpoint_z.header.stamp = stamp;
|
|
||||||
try {
|
|
||||||
tf_buffer.transform(setpoint_z, setpoint_z_transformed, local_frame, ros::Duration(0.05));
|
|
||||||
setpoint_position_transformed.pose.position.z = setpoint_z_transformed.vector.z;
|
|
||||||
|
|
||||||
} catch (const tf2::TransformException& e) {
|
|
||||||
ROS_WARN_THROTTLE(10, "can't transform z coordinate from %s to %s, ignoring z coordinate",
|
|
||||||
setpoint_z.header.frame_id.c_str(), local_frame.c_str());
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (setpoint_type == POSITION) {
|
if (setpoint_type == POSITION) {
|
||||||
position_msg = setpoint_position_transformed;
|
position_msg = setpoint_position_transformed;
|
||||||
}
|
}
|
||||||
@@ -583,7 +556,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
|||||||
|
|
||||||
// look up for reference frame
|
// look up for reference frame
|
||||||
auto search = reference_frames.find(frame_id);
|
auto search = reference_frames.find(frame_id);
|
||||||
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second; // when not found it's the same frame
|
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
|
||||||
|
|
||||||
// Serve "partial" commands
|
// Serve "partial" commands
|
||||||
|
|
||||||
@@ -610,33 +583,22 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!auto_arm && std::isfinite(z) &&
|
if (!auto_arm && std::isfinite(yaw_rate) &&
|
||||||
isnan(x) && isnan(y) && isnan(vx) && isnan(vy) && isnan(vz) &&
|
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
|
||||||
isnan(pitch) && isnan(roll) && isnan(thrust) &&
|
isnan(pitch) && isnan(roll) && isnan(yaw) && isnan(thrust) &&
|
||||||
isnan(lat) && isnan(lon)) {
|
isnan(lat) && isnan(lon)) {
|
||||||
// set only the z
|
// change only the yaw rate
|
||||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
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))
|
message = "Changing yaw rate only";
|
||||||
throw std::runtime_error("Can't transform from " + frame_id + " to " + setpoint_position.header.frame_id);
|
|
||||||
|
|
||||||
message = "Changing z only";
|
setpoint_yaw_type = YAW_RATE;
|
||||||
|
setpoint_yaw_rate = yaw_rate;
|
||||||
setpoint_z.header.frame_id = frame_id;
|
|
||||||
setpoint_z.header.stamp = stamp;
|
|
||||||
setpoint_z.vector.z = z;
|
|
||||||
setpoint_z_valid = true;
|
|
||||||
goto publish_setpoint;
|
goto publish_setpoint;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
throw std::runtime_error("Setting z is possible only when position setpoint active");
|
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints active");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// commands without z
|
|
||||||
if (isnan(z) && setpoint_z_valid && (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION)) {
|
|
||||||
z = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Serve normal commands
|
// Serve normal commands
|
||||||
|
|
||||||
if (sp_type == NAVIGATE || sp_type == POSITION) {
|
if (sp_type == NAVIGATE || sp_type == POSITION) {
|
||||||
@@ -926,7 +888,6 @@ int main(int argc, char **argv)
|
|||||||
nh_priv.param("check_kill_switch", check_kill_switch, true);
|
nh_priv.param("check_kill_switch", check_kill_switch, true);
|
||||||
nh_priv.param("default_speed", default_speed, 0.5f);
|
nh_priv.param("default_speed", default_speed, 0.5f);
|
||||||
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
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);
|
nh_priv.getParam("reference_frames", reference_frames);
|
||||||
|
|
||||||
// Default reference frames
|
// Default reference frames
|
||||||
@@ -962,13 +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 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);
|
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 = body.child_frame_id;
|
|
||||||
terrain.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, 0);
|
|
||||||
altitude_sub = nh.subscribe(mavros + "/altitude", 1, &handleAltitude);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Setpoint publishers
|
// Setpoint publishers
|
||||||
position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
|
position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
|
||||||
position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
|
position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
|
||||||
|
|||||||
@@ -25,7 +25,7 @@
|
|||||||
using std::string;
|
using std::string;
|
||||||
using namespace geometry_msgs;
|
using namespace geometry_msgs;
|
||||||
|
|
||||||
bool reset_flag = false;
|
bool reset_flag = true; // offset should be reset on the start
|
||||||
string local_frame_id, frame_id, child_frame_id, offset_frame_id;
|
string local_frame_id, frame_id, child_frame_id, offset_frame_id;
|
||||||
tf2_ros::Buffer tf_buffer;
|
tf2_ros::Buffer tf_buffer;
|
||||||
ros::Publisher vpe_pub;
|
ros::Publisher vpe_pub;
|
||||||
|
|||||||
4
clover/src/www
Executable file
4
clover/src/www
Executable file
@@ -0,0 +1,4 @@
|
|||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
export ROSWWW_DEFAULT=clover
|
||||||
|
rosrun roswww_static update
|
||||||
@@ -3,6 +3,7 @@ import rospy
|
|||||||
import pytest
|
import pytest
|
||||||
from mavros_msgs.msg import State
|
from mavros_msgs.msg import State
|
||||||
from clover import srv
|
from clover import srv
|
||||||
|
import time
|
||||||
|
|
||||||
@pytest.fixture()
|
@pytest.fixture()
|
||||||
def node():
|
def node():
|
||||||
@@ -60,3 +61,18 @@ def test_blocks(node):
|
|||||||
|
|
||||||
t.join()
|
t.join()
|
||||||
assert wait_print.result == 'test'
|
assert wait_print.result == 'test'
|
||||||
|
|
||||||
|
def test_long_callback():
|
||||||
|
from clover import long_callback
|
||||||
|
from time import sleep
|
||||||
|
|
||||||
|
# very basic test for long_callback
|
||||||
|
@long_callback
|
||||||
|
def cb(i):
|
||||||
|
cb.counter += i
|
||||||
|
cb.counter = 0
|
||||||
|
cb(2)
|
||||||
|
sleep(0.1)
|
||||||
|
cb(3)
|
||||||
|
sleep(1)
|
||||||
|
assert cb.counter == 5
|
||||||
|
|||||||
@@ -2,7 +2,7 @@
|
|||||||
<robot name="rpi_camera" xmlns:xacro="http://ros.org/wiki/xacro">
|
<robot name="rpi_camera" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||||
<xacro:include filename="../camera_sensor.urdf.xacro"/>
|
<xacro:include filename="../camera_sensor.urdf.xacro"/>
|
||||||
|
|
||||||
<xacro:macro name="distance_sensor" params="name:=lidar_vl53l1x parent x:=0 y:=0 z:=0 roll:=0 pitch:=0 yaw:=0 range_min:=0.01 range_max:=4.0 resolution:=0.01 rate:=10">
|
<xacro:macro name="distance_sensor" params="name:=lidar_vl53l1x parent x:=0 y:=0 z:=0 roll:=0 pitch:=0 yaw:=0 range_min:=0.01 range_max:=4.0 resolution:=0.01 rate:=10 fov:=0.471239">
|
||||||
<joint name="${name}_joint" type="fixed">
|
<joint name="${name}_joint" type="fixed">
|
||||||
<origin xyz="${x} ${y} ${z}"
|
<origin xyz="${x} ${y} ${z}"
|
||||||
rpy="${roll} ${pitch} ${yaw}"/>
|
rpy="${roll} ${pitch} ${yaw}"/>
|
||||||
@@ -58,7 +58,7 @@
|
|||||||
<topicName>/rangefinder/range</topicName>
|
<topicName>/rangefinder/range</topicName>
|
||||||
<frameName>rangefinder</frameName>
|
<frameName>rangefinder</frameName>
|
||||||
<radiation>infrared</radiation>
|
<radiation>infrared</radiation>
|
||||||
<fov>0.01</fov>
|
<fov>${fov}</fov>
|
||||||
<gaussianNoise>0.001</gaussianNoise>
|
<gaussianNoise>0.001</gaussianNoise>
|
||||||
<updateRate>${rate}</updateRate>
|
<updateRate>${rate}</updateRate>
|
||||||
<min_distance>${range_min}</min_distance>
|
<min_distance>${range_min}</min_distance>
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
<package format="2">
|
<package format="3">
|
||||||
<name>clover_simulation</name>
|
<name>clover_simulation</name>
|
||||||
<version>0.23.0</version>
|
<version>0.23.0</version>
|
||||||
<description>The clover_simulation package provides worlds and launch files for Gazebo.</description>
|
<description>The clover_simulation package provides worlds and launch files for Gazebo.</description>
|
||||||
@@ -22,6 +22,8 @@
|
|||||||
<depend>gazebo_ros</depend>
|
<depend>gazebo_ros</depend>
|
||||||
<depend>gazebo_plugins</depend>
|
<depend>gazebo_plugins</depend>
|
||||||
<depend>rospy</depend>
|
<depend>rospy</depend>
|
||||||
|
<depend condition="$ROS_PYTHON_VERSION == 2">python-docopt</depend>
|
||||||
|
<depend condition="$ROS_PYTHON_VERSION == 3">python3-docopt</depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
<gazebo_ros gazebo_media_path="${prefix}"/>
|
<gazebo_ros gazebo_media_path="${prefix}"/>
|
||||||
|
|||||||
@@ -65,7 +65,8 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
role = (ros::this_node::getName() == "/gazebo") ? Role::Server : Role::Client;
|
role = (ros::this_node::getName() == "/gazebo") ? Role::Server : Role::Client;
|
||||||
ROS_INFO_NAMED(("LedController_" + robotNamespace).c_str(), "LedController has started (as %s)", role == Role::Client ? "client" : "server");
|
ROS_INFO_NAMED(("LedController_" + robotNamespace).c_str(), "LedController has started (as %s) in namespace '%s'",
|
||||||
|
role == Role::Client ? "client" : "server", robotNamespace.c_str());
|
||||||
|
|
||||||
nh.reset(new ros::NodeHandle(robotNamespace));
|
nh.reset(new ros::NodeHandle(robotNamespace));
|
||||||
|
|
||||||
@@ -109,7 +110,6 @@ LedController& get(std::string robotNamespace)
|
|||||||
std::lock_guard<std::mutex> lock(controllerMutex);
|
std::lock_guard<std::mutex> lock(controllerMutex);
|
||||||
auto it = controllers.find(robotNamespace);
|
auto it = controllers.find(robotNamespace);
|
||||||
if (it == controllers.end()) {
|
if (it == controllers.end()) {
|
||||||
gzwarn << "Creating new LED controller for namespace " << robotNamespace << "\n";
|
|
||||||
controllers[robotNamespace].reset(new LedController(robotNamespace));
|
controllers[robotNamespace].reset(new LedController(robotNamespace));
|
||||||
return *controllers[robotNamespace];
|
return *controllers[robotNamespace];
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -20,7 +20,7 @@ The main goal of the contest is aerial robotics popularization and community de
|
|||||||
* Third parties can provide technical support for recording a lecture.
|
* Third parties can provide technical support for recording a lecture.
|
||||||
* The status of the participant is unlimited (student, representative of a general education institution, representative of the industry, amateur).
|
* The status of the participant is unlimited (student, representative of a general education institution, representative of the industry, amateur).
|
||||||
|
|
||||||
Applications deadline: September 1, 2022.
|
Applications deadline: November 30, 2022.
|
||||||
|
|
||||||
### How to apply?
|
### How to apply?
|
||||||
|
|
||||||
@@ -64,7 +64,7 @@ The main goal of the contest is aerial robotics popularization and community de
|
|||||||
|
|
||||||
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform).
|
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform).
|
||||||
|
|
||||||
Applications deadline: September 1, 2022.
|
Applications deadline: November 30, 2022.
|
||||||
|
|
||||||
### Prizes
|
### Prizes
|
||||||
|
|
||||||
@@ -105,7 +105,7 @@ The course is evaluated according to a separate, publicly available lesson submi
|
|||||||
|
|
||||||
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform) where the link to the video course should be attached.
|
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform) where the link to the video course should be attached.
|
||||||
|
|
||||||
Applications deadline: September 1, 2022.
|
Applications deadline: November 30, 2022.
|
||||||
|
|
||||||
### Prizes
|
### Prizes
|
||||||
|
|
||||||
|
|||||||
@@ -103,7 +103,7 @@ Parameters:
|
|||||||
* `yaw_rate` – angular yaw velocity (will be used if yaw is set to `NaN`) *(rad/s)*;
|
* `yaw_rate` – angular yaw velocity (will be used if yaw is set to `NaN`) *(rad/s)*;
|
||||||
* `speed` – flight speed (setpoint speed) *(m/s)*;
|
* `speed` – flight speed (setpoint speed) *(m/s)*;
|
||||||
* `auto_arm` – switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
|
* `auto_arm` – switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
|
||||||
* `frame_id` – [coordinate system](frames.md) for values `x`, `y`, `z`, `vx`, `vy`, `vz`. Example: `map`, `body`, `aruco_map`. Default value: `map`.
|
* `frame_id` – [coordinate system](frames.md) for values `x`, `y`, `z` and `yaw`. Example: `map`, `body`, `aruco_map`. Default value: `map`.
|
||||||
|
|
||||||
> **Note** If you don't want to change your current yaw set the `yaw` parameter to `NaN` (angular velocity by default is 0).
|
> **Note** If you don't want to change your current yaw set the `yaw` parameter to `NaN` (angular velocity by default is 0).
|
||||||
|
|
||||||
|
|||||||
@@ -147,6 +147,8 @@ sudo systemctl enable roscore
|
|||||||
sudo systemctl start roscore
|
sudo systemctl start roscore
|
||||||
```
|
```
|
||||||
|
|
||||||
|
### Web tools setup
|
||||||
|
|
||||||
Install any web server to serve Clover's web tools (`~/.ros/www` directory), e. g. Monkey:
|
Install any web server to serve Clover's web tools (`~/.ros/www` directory), e. g. Monkey:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
@@ -158,3 +160,11 @@ sudo cp ~/catkin_ws/src/clover/builder/assets/monkey.service /etc/systemd/system
|
|||||||
sudo systemctl enable monkey
|
sudo systemctl enable monkey
|
||||||
sudo systemctl start monkey
|
sudo systemctl start monkey
|
||||||
```
|
```
|
||||||
|
|
||||||
|
Create `~/.ros/www` using the following command:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
rosrun clover www
|
||||||
|
```
|
||||||
|
|
||||||
|
If the set of packages containing a web part (through `www` directory) is changed, the above command also must be run.
|
||||||
|
|||||||
@@ -207,9 +207,9 @@ def pose_update(pose):
|
|||||||
# Processing new data of copter's position
|
# Processing new data of copter's position
|
||||||
pass
|
pass
|
||||||
|
|
||||||
rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update)
|
rospy.Subscriber('mavros/local_position/pose', PoseStamped, pose_update)
|
||||||
rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update)
|
rospy.Subscriber('mavros/local_position/velocity', TwistStamped, velocity_update)
|
||||||
rospy.Subscriber('/mavros/battery', BatteryState, battery_update)
|
rospy.Subscriber('mavros/battery', BatteryState, battery_update)
|
||||||
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
|
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
|
||||||
|
|
||||||
rospy.spin()
|
rospy.spin()
|
||||||
@@ -349,7 +349,7 @@ from pymavlink import mavutil
|
|||||||
from mavros_msgs.srv import CommandLong
|
from mavros_msgs.srv import CommandLong
|
||||||
from mavros_msgs.msg import State
|
from mavros_msgs.msg import State
|
||||||
|
|
||||||
send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
|
send_command = rospy.ServiceProxy('mavros/cmd/command', CommandLong)
|
||||||
|
|
||||||
def calibrate_gyro():
|
def calibrate_gyro():
|
||||||
rospy.loginfo('Calibrate gyro')
|
rospy.loginfo('Calibrate gyro')
|
||||||
@@ -480,3 +480,11 @@ param_set(param_id='COM_FLTMODE1', value=ParamValue(integer=8))
|
|||||||
# Set parameter of type FLOAT:
|
# Set parameter of type FLOAT:
|
||||||
param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
|
param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
|
||||||
```
|
```
|
||||||
|
|
||||||
|
### # {#is-simulation}
|
||||||
|
|
||||||
|
Check, if the code is running inside a [Gazebo simulation](simulation.md):
|
||||||
|
|
||||||
|
```python
|
||||||
|
is_simulation = rospy.get_param('/use_sim_time', False)
|
||||||
|
```
|
||||||
|
|||||||
@@ -49,10 +49,10 @@ If you are using the marker map, where the markers have equal distances along th
|
|||||||
|
|
||||||
After you fill out the map, you need to apply it. To do it, edit the file `aruco.launch`, located in `~/catkin_ws/src/clover/clover/launch/`. Change the line `<param name="map" value="$(find aruco_pose)/map/map_name.txt"/>`, where `map_name.txt` is the name of your map file.
|
After you fill out the map, you need to apply it. To do it, edit the file `aruco.launch`, located in `~/catkin_ws/src/clover/clover/launch/`. Change the line `<param name="map" value="$(find aruco_pose)/map/map_name.txt"/>`, where `map_name.txt` is the name of your map file.
|
||||||
|
|
||||||
If you are using markers that are not linked to horizontal surfaces (floor, ceiling), you must disable the parameter `known_tilt` both in the module `aruco_detect` and `aruco_map` in the same file. To do it automatically, enter:
|
If you are using markers that are not linked to horizontal surfaces (floor, ceiling), you must blank the `placement` argument in the same file:
|
||||||
|
|
||||||
```bash
|
```xml
|
||||||
sed -i "/known_tilt/s/value=\".*\"/value=\"\"/" /home/pi/catkin_ws/src/clover/clover/launch/aruco.launch
|
<arg name="placement" default=""/>
|
||||||
```
|
```
|
||||||
|
|
||||||
After all the settings, call `sudo systemctl restart clover` to restart the `clover` service.
|
After all the settings, call `sudo systemctl restart clover` to restart the `clover` service.
|
||||||
|
|||||||
@@ -26,7 +26,7 @@
|
|||||||
|
|
||||||
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLScE2kN5dO2OYNSM8hOYzOa5Qvh2uDdd9Fjx8OnL1W93bfEBgw/viewform).
|
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLScE2kN5dO2OYNSM8hOYzOa5Qvh2uDdd9Fjx8OnL1W93bfEBgw/viewform).
|
||||||
|
|
||||||
Дедлайн подачи заявок: 1 сентября 2022 года.
|
Дедлайн подачи заявок: 30 ноября 2022 года.
|
||||||
|
|
||||||
### Призы
|
### Призы
|
||||||
|
|
||||||
@@ -64,7 +64,7 @@
|
|||||||
|
|
||||||
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform).
|
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform).
|
||||||
|
|
||||||
Дедлайн подачи заявок: 1 сентября 2022 года.
|
Дедлайн подачи заявок: 30 ноября 2022 года.
|
||||||
|
|
||||||
### Призы
|
### Призы
|
||||||
|
|
||||||
@@ -106,7 +106,7 @@
|
|||||||
|
|
||||||
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform).
|
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform).
|
||||||
|
|
||||||
Дедлайн подачи заявок: 1 сентября 2022 года
|
Дедлайн подачи заявок: 30 ноября 2022 года
|
||||||
|
|
||||||
### Призы
|
### Призы
|
||||||
|
|
||||||
|
|||||||
@@ -147,6 +147,8 @@ sudo systemctl enable roscore
|
|||||||
sudo systemctl start roscore
|
sudo systemctl start roscore
|
||||||
```
|
```
|
||||||
|
|
||||||
|
### Конфигурация веб-инструментов
|
||||||
|
|
||||||
Установите любой веб-сервер, чтобы раздавать веб-инструменты Клевера (директория `~/.ros/www`), например, Monkey:
|
Установите любой веб-сервер, чтобы раздавать веб-инструменты Клевера (директория `~/.ros/www`), например, Monkey:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
@@ -158,3 +160,11 @@ sudo cp ~/catkin_ws/src/clover/builder/assets/monkey.service /etc/systemd/system
|
|||||||
sudo systemctl enable monkey
|
sudo systemctl enable monkey
|
||||||
sudo systemctl start monkey
|
sudo systemctl start monkey
|
||||||
```
|
```
|
||||||
|
|
||||||
|
Создайте директорию `~/.ros/www` следующей командой:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
rosrun clover www
|
||||||
|
```
|
||||||
|
|
||||||
|
При обновлении набора пакетов, содержащих веб-часть (через каталог `www`), также необходимо выполнение данной команды.
|
||||||
|
|||||||
@@ -217,9 +217,9 @@ def pose_update(pose):
|
|||||||
# Обработка новых данных о позиции коптера
|
# Обработка новых данных о позиции коптера
|
||||||
pass
|
pass
|
||||||
|
|
||||||
rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update)
|
rospy.Subscriber('mavros/local_position/pose', PoseStamped, pose_update)
|
||||||
rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update)
|
rospy.Subscriber('mavros/local_position/velocity', TwistStamped, velocity_update)
|
||||||
rospy.Subscriber('/mavros/battery', BatteryState, battery_update)
|
rospy.Subscriber('mavros/battery', BatteryState, battery_update)
|
||||||
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
|
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
|
||||||
|
|
||||||
rospy.spin()
|
rospy.spin()
|
||||||
@@ -360,7 +360,7 @@ from pymavlink import mavutil
|
|||||||
from mavros_msgs.srv import CommandLong
|
from mavros_msgs.srv import CommandLong
|
||||||
from mavros_msgs.msg import State
|
from mavros_msgs.msg import State
|
||||||
|
|
||||||
send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
|
send_command = rospy.ServiceProxy('mavros/cmd/command', CommandLong)
|
||||||
|
|
||||||
def calibrate_gyro():
|
def calibrate_gyro():
|
||||||
rospy.loginfo('Calibrate gyro')
|
rospy.loginfo('Calibrate gyro')
|
||||||
@@ -491,3 +491,11 @@ param_set(param_id='COM_FLTMODE1', value=ParamValue(integer=8))
|
|||||||
# Изменить параметр типа FLOAT:
|
# Изменить параметр типа FLOAT:
|
||||||
param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
|
param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
|
||||||
```
|
```
|
||||||
|
|
||||||
|
### # {#is-simulation}
|
||||||
|
|
||||||
|
Проверить, что код запущен в [симуляции Gazebo](simulation.md):
|
||||||
|
|
||||||
|
```python
|
||||||
|
is_simulation = rospy.get_param('/use_sim_time', False)
|
||||||
|
```
|
||||||
|
|||||||
@@ -51,10 +51,10 @@ sed -i "/direction_y/s/default=\".*\"/default=\"\"/" /home/pi/catkin_ws/src/clov
|
|||||||
|
|
||||||
После того, как вы заполните карту, необходимо применить ее — для этого отредактируйте файл `aruco.launch`, расположенный в `~/catkin_ws/src/clover/clover/launch/`. Измените в нем строку `<param name="map" value="$(find aruco_pose)/map/map_name.txt"/>`, где `map_name.txt` название вашего файла с картой.
|
После того, как вы заполните карту, необходимо применить ее — для этого отредактируйте файл `aruco.launch`, расположенный в `~/catkin_ws/src/clover/clover/launch/`. Измените в нем строку `<param name="map" value="$(find aruco_pose)/map/map_name.txt"/>`, где `map_name.txt` название вашего файла с картой.
|
||||||
|
|
||||||
При использовании маркеров, не привязанных к горизонтальным плоскостям(пол, потолок), необходимо отключить параметр `known_tilt` как в модуле `aruco_detect`, так и в модуле `aruco_map` в том же файле. Для того, чтобы сделать это автоматически, введите:
|
При использовании маркеров, не привязанных к горизонтальным плоскостям (пол, потолок), необходимо также сделать пустым значение аргумента `placement` в том же файле:
|
||||||
|
|
||||||
```bash
|
```xml
|
||||||
sed -i "/known_tilt/s/value=\".*\"/value=\"\"/" /home/pi/catkin_ws/src/clover/clover/launch/aruco.launch
|
<arg name="placement" default=""/>
|
||||||
```
|
```
|
||||||
|
|
||||||
После всех настроек вызовите `sudo systemctl restart clover` для перезагрузки сервиса `clover`.
|
После всех настроек вызовите `sudo systemctl restart clover` для перезагрузки сервиса `clover`.
|
||||||
|
|||||||
@@ -35,7 +35,7 @@
|
|||||||
{ "from": "snippets.html", "to": "ru/snippets.html" },
|
{ "from": "snippets.html", "to": "ru/snippets.html" },
|
||||||
{ "from": "camera_frame.html", "to": "ru/camera_setup.html" },
|
{ "from": "camera_frame.html", "to": "ru/camera_setup.html" },
|
||||||
{ "from": "ru/camera_frame.html", "to": "camera_setup.html" },
|
{ "from": "ru/camera_frame.html", "to": "camera_setup.html" },
|
||||||
{ "from": "camera.html", "to": "ru/camera.html" },
|
{ "from": "camera.html", "to": "en/camera.html" },
|
||||||
{ "from": "led.html", "to": "en/leds.html" },
|
{ "from": "led.html", "to": "en/leds.html" },
|
||||||
{ "from": "leds.html", "to": "ru/leds.html" },
|
{ "from": "leds.html", "to": "ru/leds.html" },
|
||||||
{ "from": "rviz.html", "to": "ru/rviz.html" },
|
{ "from": "rviz.html", "to": "ru/rviz.html" },
|
||||||
@@ -51,7 +51,7 @@
|
|||||||
{ "from": "firmware/", "to": "en/firmware.html" },
|
{ "from": "firmware/", "to": "en/firmware.html" },
|
||||||
{ "from": "simple_offboard/", "to": "en/simple_offboard.html" },
|
{ "from": "simple_offboard/", "to": "en/simple_offboard.html" },
|
||||||
{ "from": "offboard/", "to": "en/simple_offboard.html" },
|
{ "from": "offboard/", "to": "en/simple_offboard.html" },
|
||||||
{ "from": "camera/", "to": "ru/camera.html" },
|
{ "from": "camera/", "to": "en/camera.html" },
|
||||||
{ "from": "snippets/", "to": "ru/snippets.html" },
|
{ "from": "snippets/", "to": "ru/snippets.html" },
|
||||||
{ "from": "optical_flow/", "to": "ru/optical_flow.html" },
|
{ "from": "optical_flow/", "to": "ru/optical_flow.html" },
|
||||||
{ "from": "laser/", "to": "ru/laser.html" },
|
{ "from": "laser/", "to": "ru/laser.html" },
|
||||||
|
|||||||
@@ -5,8 +5,6 @@ find_package(catkin REQUIRED)
|
|||||||
|
|
||||||
catkin_package()
|
catkin_package()
|
||||||
|
|
||||||
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
catkin_install_python(PROGRAMS src/update
|
||||||
|
|
||||||
catkin_install_python(PROGRAMS main.py
|
|
||||||
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -6,12 +6,14 @@ Note: you should configure your web server to make it follow symlinks.
|
|||||||
|
|
||||||
## Instructions
|
## Instructions
|
||||||
|
|
||||||
* Run `main.py` node and it will generate the symlinks and index file.
|
* Run `update` script and it will generate the symlinks and index file: `rosrun roswww_static update`.
|
||||||
* Point your static web server path to `~/.ros/www`.
|
* Point your static web server path to `~/.ros/www`.
|
||||||
|
|
||||||
You can rerun `main.py` if the list of installed packages changes.
|
You can rerun `update` if the list of installed packages changes.
|
||||||
|
|
||||||
## Parameters
|
## Parameters
|
||||||
|
|
||||||
* `index` – path for index page, otherwise packages list would be generated.
|
Parameters are passed through environment variables:
|
||||||
* `default_package` – if set then the index page would redirect to this package's page.
|
|
||||||
|
* `ROSWWW_INDEX` – path for index page, otherwise packages list would be generated.
|
||||||
|
* `ROSWWW_DEFAULT` – if set then the index page would redirect to this package's page.
|
||||||
|
|||||||
@@ -1,6 +0,0 @@
|
|||||||
<launch>
|
|
||||||
<node pkg="roswww_static" name="roswww_static" type="main.py" clear_params="true" output="screen">
|
|
||||||
<!-- <param name="index" value="$(find my_package)/www/index.html"/> -->
|
|
||||||
<!-- <param name="default_package" value="my_package"/> -->
|
|
||||||
</node>
|
|
||||||
</launch>
|
|
||||||
@@ -13,17 +13,15 @@
|
|||||||
|
|
||||||
import os
|
import os
|
||||||
import shutil
|
import shutil
|
||||||
import rospy
|
|
||||||
import rospkg
|
import rospkg
|
||||||
|
|
||||||
rospy.init_node('roswww_static')
|
|
||||||
|
|
||||||
rospack = rospkg.RosPack()
|
rospack = rospkg.RosPack()
|
||||||
|
|
||||||
www = rospkg.get_ros_home() + '/www'
|
www = rospkg.get_ros_home() + '/www'
|
||||||
index_file = rospy.get_param('~index_file', None)
|
index_file = os.environ.get('ROSWWW_INDEX')
|
||||||
default_package = rospy.get_param('~default_package', None)
|
default_package = os.environ.get('ROSWWW_DEFAULT')
|
||||||
|
|
||||||
|
print('using www dir: ' + www)
|
||||||
shutil.rmtree(www, ignore_errors=True) # reset www directory content
|
shutil.rmtree(www, ignore_errors=True) # reset www directory content
|
||||||
os.mkdir(www)
|
os.mkdir(www)
|
||||||
|
|
||||||
@@ -34,7 +32,7 @@ index = '<h1>Packages list</h1>\n<ul>\n'
|
|||||||
for name in packages:
|
for name in packages:
|
||||||
path = rospack.get_path(name)
|
path = rospack.get_path(name)
|
||||||
if os.path.exists(path + '/www'):
|
if os.path.exists(path + '/www'):
|
||||||
rospy.loginfo('found www path for %s package', name)
|
print('found www path for %s package' % name)
|
||||||
os.symlink(path + '/www', www + '/' + name)
|
os.symlink(path + '/www', www + '/' + name)
|
||||||
index += '<li><a href="{name}/">{name}</a></li>'.format(name=name)
|
index += '<li><a href="{name}/">{name}</a></li>'.format(name=name)
|
||||||
|
|
||||||
@@ -42,7 +40,7 @@ if default_package is not None:
|
|||||||
redirect_html = '<meta http-equiv=refresh content="0; url={name}/">'.format(name=default_package)
|
redirect_html = '<meta http-equiv=refresh content="0; url={name}/">'.format(name=default_package)
|
||||||
open(www + '/index.html', 'w').write(redirect_html)
|
open(www + '/index.html', 'w').write(redirect_html)
|
||||||
elif index_file is not None:
|
elif index_file is not None:
|
||||||
rospy.loginfo('symlinking index file')
|
print('symlinking index file')
|
||||||
os.symlink(index_file, www + '/index.html')
|
os.symlink(index_file, www + '/index.html')
|
||||||
else:
|
else:
|
||||||
open(www + '/index.html', 'w').write(index)
|
open(www + '/index.html', 'w').write(index)
|
||||||
Reference in New Issue
Block a user