Compare commits

...

11 Commits

Author SHA1 Message Date
Oleg Kalachev
a72cb67d03 Fix editorconfig 2022-11-11 14:57:18 +06:00
Oleg Kalachev
8ac757598d selfcheck.py: fix known_vertical description 2022-11-11 06:22:54 +06:00
Oleg Kalachev
25c3f25642 aruco_pose: document flip_vertical parameter 2022-11-11 06:00:18 +06:00
Oleg Kalachev
4877d0101b Merge branch 'master' into known_vertical 2022-11-11 05:59:02 +06:00
Oleg Kalachev
8fd69e4ea5 selfcheck.py: support flip_vertical parameter 2022-11-11 05:58:09 +06:00
Oleg Kalachev
c3625490b2 Merge branch 'master' into known_vertical 2022-11-11 05:47:12 +06:00
Oleg Kalachev
cf62364ac7 aruco_pose: add flip_vertical parameter and get rid of map_flipped 2022-11-11 05:41:46 +06:00
Oleg Kalachev
c7bf964ea5 More clean variable names 2022-11-11 02:33:37 +06:00
Oleg Kalachev
5ec04bbefa Merge branch 'master' into known_vertical 2022-11-10 19:58:01 +06:00
Oleg Kalachev
275023b455 Merge branch 'master' into known_vertical 2022-11-10 18:04:56 +06:00
Oleg Kalachev
b3b530c1c7 aruco_pose: rename parameter known_tilt to known_vertical 2022-11-10 05:12:59 +06:00
6 changed files with 62 additions and 56 deletions

View File

@@ -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)

View File

@@ -71,12 +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_, use_map_markers_; bool estimate_poses_, send_tf_, flip_vertical_, auto_flip_, use_map_markers_;
bool waiting_for_map_; 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_;
@@ -105,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_");
@@ -144,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);
@@ -179,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());
} }
} }
} }
@@ -205,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_) {

View File

@@ -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;

View File

@@ -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)

View File

@@ -19,8 +19,8 @@
<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="use_map_markers" value="true"/> <param name="use_map_markers" value="true"/>
<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="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 -->
@@ -36,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)"/>
@@ -53,8 +53,4 @@
<param name="force_init" value="$(arg force_init)"/> <param name="force_init" value="$(arg force_init)"/>
<param name="offset_frame_id" value="aruco_map"/> <param name="offset_frame_id" value="aruco_map"/>
</node> </node>
<!-- run map_flipped frame if placement is ceiling -->
<node pkg="tf2_ros" type="static_transform_publisher" name="map_flipped_frame"
args="0 0 0 3.1415926 3.1415926 0 map map_flipped" if="$(eval placement == 'ceiling')"/>
</launch> </launch>

View File

@@ -401,12 +401,15 @@ def check_aruco():
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_detect/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:
markers = rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=0.8) markers = rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=0.8)
except rospy.ROSException: except rospy.ROSException:
@@ -417,12 +420,15 @@ 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=0.8) visualization = rospy.wait_for_message('aruco_map/visualization', VisualizationMarkerArray, timeout=0.8)
@@ -462,7 +468,8 @@ def check_vpe():
except rospy.ROSException: except rospy.ROSException:
if not is_process_running('vpe_publisher', full=True): if not is_process_running('vpe_publisher', full=True):
info('no vision position estimate, vpe_publisher is not running') info('no vision position estimate, vpe_publisher is not running')
elif rospy.get_param('aruco_map/known_tilt', '') == 'map_flipped': elif rospy.get_param('aruco_map/known_vertical', '') == 'map' \
and rospy.get_param('aruco_map/flip_vertical', False):
failure('no vision position estimate, markers are on the ceiling') failure('no vision position estimate, markers are on the ceiling')
elif is_on_the_floor(): elif is_on_the_floor():
info('no vision position estimate, the drone is on the floor') info('no vision position estimate, the drone is on the floor')