update
This commit is contained in:
@@ -31,6 +31,7 @@ if (NOT BUILDING_WITH_CATKIN)
|
||||
robot_geometry_msgs
|
||||
robot_protocol_msgs
|
||||
robot_nav_2d_msgs
|
||||
robot_nav_2d_utils
|
||||
robot_nav_msgs
|
||||
robot_sensor_msgs
|
||||
)
|
||||
@@ -41,17 +42,19 @@ else()
|
||||
# Catkin specific configuration
|
||||
# ========================================================
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
tf3
|
||||
robot_time
|
||||
robot_geometry_msgs
|
||||
robot_protocol_msgs
|
||||
robot_nav_2d_msgs
|
||||
robot_nav_2d_utils
|
||||
)
|
||||
find_package(tf3)
|
||||
|
||||
catkin_package(
|
||||
INCLUDE_DIRS include
|
||||
# LIBRARIES không cần vì đây là header-only library
|
||||
CATKIN_DEPENDS tf3 robot_time robot_geometry_msgs robot_protocol_msgs robot_nav_2d_msgs
|
||||
CATKIN_DEPENDS robot_time robot_geometry_msgs robot_protocol_msgs robot_nav_2d_msgs
|
||||
DEPENDS tf3
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
||||
@@ -18,6 +18,7 @@
|
||||
#include <robot_sensor_msgs/PointCloud.h>
|
||||
#include <robot_sensor_msgs/PointCloud2.h>
|
||||
#include <robot_protocol_msgs/Order.h>
|
||||
#include <robot_nav_2d_utils/conversions.h>
|
||||
|
||||
// tf
|
||||
#include <tf3/buffer_core.h>
|
||||
@@ -138,10 +139,7 @@ namespace robot
|
||||
goal.header.stamp = robot::Time::now();
|
||||
goal.pose.position.x = pose.x + offset_distance * cos(pose.theta);
|
||||
goal.pose.position.y = pose.y + offset_distance * sin(pose.theta);
|
||||
|
||||
tf3::Quaternion q;
|
||||
q.setRPY(0, 0, pose.theta);
|
||||
goal.pose.orientation = tf3::toMsg(q);
|
||||
goal.pose.orientation = robot_nav_2d_utils::pose2DToPose(pose).orientation;
|
||||
return goal;
|
||||
}
|
||||
|
||||
@@ -161,7 +159,7 @@ namespace robot
|
||||
robot_geometry_msgs::Pose2D pose2d;
|
||||
pose2d.x = pose.pose.position.x;
|
||||
pose2d.y = pose.pose.position.y;
|
||||
// pose2d.theta = tf2::getYaw(pose.pose.orientation);
|
||||
pose2d.theta = robot_nav_2d_utils::poseStampedToPose2D(pose).pose.theta;
|
||||
return offset_goal(pose2d, pose.header.frame_id, offset_distance);
|
||||
}
|
||||
|
||||
|
||||
@@ -29,6 +29,7 @@
|
||||
<build_depend>robot_geometry_msgs</build_depend>
|
||||
<build_depend>robot_protocol_msgs</build_depend>
|
||||
<build_depend>robot_nav_2d_msgs</build_depend>
|
||||
<build_depend>robot_nav_2d_utils</build_depend>
|
||||
<build_depend>robot_nav_msgs</build_depend>
|
||||
<build_depend>robot_sensor_msgs</build_depend>
|
||||
<build_depend>robot_map_msgs</build_depend>
|
||||
@@ -38,6 +39,7 @@
|
||||
<run_depend>robot_geometry_msgs</run_depend>
|
||||
<run_depend>robot_protocol_msgs</run_depend>
|
||||
<run_depend>robot_nav_2d_msgs</run_depend>
|
||||
<run_depend>robot_nav_2d_utils</run_depend>
|
||||
<run_depend>robot_nav_msgs</run_depend>
|
||||
<run_depend>robot_sensor_msgs</run_depend>
|
||||
<run_depend>robot_map_msgs</run_depend>
|
||||
|
||||
Reference in New Issue
Block a user