Skip to content
Snippets Groups Projects
Commit 5f54386d authored by Weizhang Luo's avatar Weizhang Luo
Browse files

robot sample app : inventory scan : add QR code scan support

Change-Id: Idc51d1d1a347ebe02819917a1fa26a0e8115014b
parent 0c695eb8
No related branches found
No related tags found
No related merge requests found
...@@ -36,6 +36,7 @@ public: ...@@ -36,6 +36,7 @@ public:
PathManager() = default; PathManager() = default;
bool add_station(uint32_t id, const Point2D& pos); bool add_station(uint32_t id, const Point2D& pos);
void get_station(uint32_t id, Point2D& pos);
bool delete_station(uint32_t id); bool delete_station(uint32_t id);
void get_stations(std::unordered_map<uint32_t, Point2D>& station); void get_stations(std::unordered_map<uint32_t, Point2D>& station);
bool add_path(uint32_t id1, uint32_t id2); bool add_path(uint32_t id1, uint32_t id2);
...@@ -57,8 +58,8 @@ class NaviState ...@@ -57,8 +58,8 @@ class NaviState
public: public:
const static uint32_t IDLE = 0; const static uint32_t IDLE = 0;
const static uint32_t NAVIGATING = 1; const static uint32_t NAVIGATING = 1;
const static uint32_t NAVI_PHASE_DONE = 2; const static uint32_t GOING_HOME = 2;
const static uint32_t GOING_HOME = 3; const static uint32_t NAVI_ERR = 3;
NaviState(); NaviState();
uint32_t get_state(void); uint32_t get_state(void);
......
...@@ -33,6 +33,7 @@ class PathManagerNode : public rclcpp::Node ...@@ -33,6 +33,7 @@ class PathManagerNode : public rclcpp::Node
public: public:
using PathService = inventory_scan_msgs::srv::ScanPath; using PathService = inventory_scan_msgs::srv::ScanPath;
using VirtualPath = qrb_ros_navigation_msgs::srv::VirtualPath; using VirtualPath = qrb_ros_navigation_msgs::srv::VirtualPath;
using VirtualPathFuture = rclcpp::Client<VirtualPath>::SharedFuture;
explicit PathManagerNode(std::shared_ptr<PathManager> path, explicit PathManagerNode(std::shared_ptr<PathManager> path,
std::shared_ptr<NaviState> navi_state); std::shared_ptr<NaviState> navi_state);
~PathManagerNode() = default; ~PathManagerNode() = default;
...@@ -45,17 +46,26 @@ private: ...@@ -45,17 +46,26 @@ private:
rclcpp::Client<VirtualPath>::SharedPtr vp_client_{ nullptr }; rclcpp::Client<VirtualPath>::SharedPtr vp_client_{ nullptr };
std::unique_ptr<tf2_ros::Buffer> tf_buffer_; std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_; std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::CallbackGroup::SharedPtr callback_group_;
std::mutex lock_;
std::condition_variable cv_;
uint8_t vp_response_ret_;
void service_callback(const std::shared_ptr<rmw_request_id_t> request_header, void service_callback(const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<PathService::Request> request, const std::shared_ptr<PathService::Request> request,
std::shared_ptr<PathService::Response> response); std::shared_ptr<PathService::Response> response);
uint32_t virtual_path_add_station(const Point2D & pos); void init_station_list(std::vector<uint32_t>& list, size_t& len);
uint32_t virtual_path_delete_station(uint32_t id); void init_station(const std::vector<uint32_t>& list, size_t len);
bool query_pose(Point2D & pos); void init_path(const std::vector<uint32_t>& list, size_t len);
void virtual_path_add_path(uint32_t id1, uint32_t id2); uint32_t virtual_path_add_station(const Point2D& pos);
void virtual_path_delete_path(uint32_t id1, uint32_t id2); bool virtual_path_delete_station(uint32_t id);
void virtual_path_add_full_path(const std::vector<uint32_t> & path); bool query_pose(Point2D& pos);
bool virtual_path_add_path(uint32_t id1, uint32_t id2);
bool virtual_path_delete_path(uint32_t id1, uint32_t id2);
void init();
}; };
class ScanNode : public rclcpp::Node class ScanNode : public rclcpp::Node
...@@ -72,7 +82,7 @@ private: ...@@ -72,7 +82,7 @@ private:
void goal_response_callback(GoalHandleVision::SharedPtr handle); void goal_response_callback(GoalHandleVision::SharedPtr handle);
void feedback_callback(GoalHandleVision::SharedPtr handle, void feedback_callback(GoalHandleVision::SharedPtr handle,
const std::shared_ptr<const VisionAction::Feedback> feedback); const std::shared_ptr<const VisionAction::Feedback> feedback);
void result_callback(const GoalHandleVision::WrappedResult & result); void result_callback(const GoalHandleVision::WrappedResult& result);
void execute(void); void execute(void);
std::shared_ptr<SyncState> sync_state_; std::shared_ptr<SyncState> sync_state_;
...@@ -83,6 +93,11 @@ private: ...@@ -83,6 +93,11 @@ private:
class NaviNode : public rclcpp::Node class NaviNode : public rclcpp::Node
{ {
public: public:
const static uint32_t NAVI_IDLE = 0;
const static uint32_t NAVI_START = 1;
const static uint32_t NAVI_FINISH = 2;
const static uint32_t NAVI_ERROR = 3;
using NaviService = inventory_scan_msgs::srv::ScanControl; using NaviService = inventory_scan_msgs::srv::ScanControl;
// navigation includes p2p and followpth // navigation includes p2p and followpth
...@@ -103,6 +118,7 @@ private: ...@@ -103,6 +118,7 @@ private:
std::shared_ptr<NaviService::Response> response); std::shared_ptr<NaviService::Response> response);
void execute(const std::vector<uint32_t>& full_path); void execute(const std::vector<uint32_t>& full_path);
void go_home();
// for Navigation Action client // for Navigation Action client
rclcpp_action::Client<NavigateToPose>::SharedPtr navi_client_{ nullptr }; rclcpp_action::Client<NavigateToPose>::SharedPtr navi_client_{ nullptr };
GoalHandleNavigate::SharedPtr goal_handle_; GoalHandleNavigate::SharedPtr goal_handle_;
...@@ -110,21 +126,31 @@ private: ...@@ -110,21 +126,31 @@ private:
void navi_feedback_callback(GoalHandleNavigate::SharedPtr, void navi_feedback_callback(GoalHandleNavigate::SharedPtr,
const std::shared_ptr<const NavigateToPose::Feedback> feedback); const std::shared_ptr<const NavigateToPose::Feedback> feedback);
void navi_result_callback(const GoalHandleNavigate::WrappedResult & result); void navi_result_callback(const GoalHandleNavigate::WrappedResult & result);
void init();
// compute path service client // compute path service client
rclcpp::Client<ComputeFollowPath>::SharedPtr fp_client_{ nullptr }; rclcpp::Client<ComputeFollowPath>::SharedPtr fp_client_{ nullptr };
rclcpp::Client<ComputeP2pPath>::SharedPtr p2p_client_{ nullptr }; rclcpp::Client<ComputeP2pPath>::SharedPtr p2p_client_{ nullptr };
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::CallbackGroup::SharedPtr callback_group_;
std::shared_ptr<NaviState> navi_state_; std::shared_ptr<NaviState> navi_state_;
std::shared_ptr<PathManager> path_; std::shared_ptr<PathManager> path_;
std::shared_ptr<SyncState> sync_state_; std::shared_ptr<SyncState> sync_state_;
uint32_t navi_result_;
bool navi_server_ready_;
std::mutex lock_;
std::condition_variable cv_;
}; };
class PubNode : public rclcpp::Node class PubNode : public rclcpp::Node
{ {
public: public:
explicit PubNode(std::shared_ptr<MapManager> map_manager, explicit PubNode(std::shared_ptr<MapManager> map_manager,
std::shared_ptr<NaviState> navi_state, std::shared_ptr<GoodsManager> goods); std::shared_ptr<NaviState> navi_state,
std::shared_ptr<GoodsManager> goods);
private: private:
rclcpp::Publisher<inventory_scan_msgs::msg::ScanResult>::SharedPtr result_pub_; rclcpp::Publisher<inventory_scan_msgs::msg::ScanResult>::SharedPtr result_pub_;
......
...@@ -17,12 +17,21 @@ bool PathManager::add_station(uint32_t id, const Point2D & pos) ...@@ -17,12 +17,21 @@ bool PathManager::add_station(uint32_t id, const Point2D & pos)
auto ret = station_.insert({ id, pos }); auto ret = station_.insert({ id, pos });
lock_.unlock(); lock_.unlock();
std::cout << "add station: " << id <<std::endl;
if (!ret.second) if (!ret.second)
return false; return false;
else else
return true; return true;
} }
void PathManager::get_station(uint32_t id, Point2D& pos)
{
lock_.lock();
pos = station_.at(id);
lock_.unlock();
}
bool PathManager::delete_station(uint32_t id) bool PathManager::delete_station(uint32_t id)
{ {
lock_.lock(); lock_.lock();
...@@ -372,12 +381,13 @@ void MapManager::pose_to_pixel(const Point2D & pose, ...@@ -372,12 +381,13 @@ void MapManager::pose_to_pixel(const Point2D & pose,
double ori_y, double ori_y,
const cv::Mat & map) const cv::Mat & map)
{ {
float x = (float)(pose.x - ori_x); double x = pose.x - ori_x;
float y = (float)(pose.y - ori_y); double y = pose.y - ori_y;
// point to pixel in image // point to pixel in image
pixel.x = static_cast<int>(x / res + 0.5); pixel.x = static_cast<int>(x / res + 0.5);
pixel.y = map.rows - static_cast<int>(y / res + 0.5); //pixel.y = map.rows - static_cast<int>(y / res + 0.5);
pixel.y = static_cast<int>(y / res + 0.5);
} }
bool MapManager::is_pixel_in_image(const cv::Point & pixel, const cv::Mat & image) bool MapManager::is_pixel_in_image(const cv::Point & pixel, const cv::Mat & image)
......
This diff is collapsed.
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment