update
This commit is contained in:
@@ -497,13 +497,14 @@ namespace NavigationExample
|
|||||||
|
|
||||||
static void Main(string[] args)
|
static void Main(string[] args)
|
||||||
{
|
{
|
||||||
// Create TF listener
|
// Create TF listener (required for costmap and local planner; must be valid when calling navigation_initialize)
|
||||||
NavigationAPI.TFListenerHandle tfHandle = NavigationAPI.tf_listener_create();
|
NavigationAPI.TFListenerHandle tfHandle = NavigationAPI.tf_listener_create();
|
||||||
if (tfHandle.ptr == IntPtr.Zero)
|
if (tfHandle.ptr == IntPtr.Zero)
|
||||||
{
|
{
|
||||||
LogError("Failed to create TF listener");
|
LogError("Failed to create TF listener");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
Console.WriteLine($"[NavigationExample] TF listener created, handle = 0x{tfHandle.ptr.ToInt64():X16}");
|
||||||
|
|
||||||
// Inject a static TF so costmap can immediately canTransform(map <-> base_link).
|
// Inject a static TF so costmap can immediately canTransform(map <-> base_link).
|
||||||
// If you already publish TF from localization/odometry, you can remove this call.
|
// If you already publish TF from localization/odometry, you can remove this call.
|
||||||
@@ -543,15 +544,35 @@ namespace NavigationExample
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Initialize navigation
|
// Initialize navigation (passes TF to move_base; navigation keeps its own copy, so tfHandle can be destroyed later)
|
||||||
if (!NavigationAPI.navigation_initialize(navHandle, tfHandle))
|
if (!NavigationAPI.navigation_initialize(navHandle, tfHandle))
|
||||||
{
|
{
|
||||||
LogError("Failed to initialize navigation");
|
LogError("Failed to initialize navigation (check native log for 'Invalid TF listener' or 'tf is nullptr')");
|
||||||
NavigationAPI.navigation_destroy(navHandle);
|
NavigationAPI.navigation_destroy(navHandle);
|
||||||
NavigationAPI.tf_listener_destroy(tfHandle);
|
NavigationAPI.tf_listener_destroy(tfHandle);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
while(true)
|
||||||
|
{
|
||||||
|
// Get navigation feedback
|
||||||
|
NavigationAPI.NavFeedback feedback = new NavigationAPI.NavFeedback();
|
||||||
|
if (NavigationAPI.navigation_get_feedback(navHandle, ref feedback))
|
||||||
|
{
|
||||||
|
if(feedback.is_ready)
|
||||||
|
{
|
||||||
|
Console.WriteLine("Navigation is ready");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
Console.WriteLine("Navigation is not ready");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
System.Threading.Thread.Sleep(100);
|
||||||
|
}
|
||||||
|
Console.WriteLine("[NavigationExample] Navigation initialized with TF successfully");
|
||||||
|
|
||||||
// Set robot footprint
|
// Set robot footprint
|
||||||
NavigationAPI.Point[] footprint = new NavigationAPI.Point[]
|
NavigationAPI.Point[] footprint = new NavigationAPI.Point[]
|
||||||
{
|
{
|
||||||
@@ -562,17 +583,6 @@ namespace NavigationExample
|
|||||||
};
|
};
|
||||||
NavigationAPI.navigation_set_robot_footprint(navHandle, footprint, new UIntPtr((uint)footprint.Length));
|
NavigationAPI.navigation_set_robot_footprint(navHandle, footprint, new UIntPtr((uint)footprint.Length));
|
||||||
|
|
||||||
// Get navigation feedback
|
|
||||||
NavigationAPI.NavFeedback feedback = new NavigationAPI.NavFeedback();
|
|
||||||
if (NavigationAPI.navigation_get_feedback(navHandle, ref feedback))
|
|
||||||
{
|
|
||||||
IntPtr stateStrPtr = NavigationAPI.navigation_state_to_string(feedback.navigation_state);
|
|
||||||
string stateStr = NavigationAPI.MarshalString(stateStrPtr);
|
|
||||||
NavigationAPI.nav_c_api_free_string(stateStrPtr);
|
|
||||||
string feedbackStr = NavigationAPI.MarshalString(feedback.feed_back_str);
|
|
||||||
Console.WriteLine($"State: {stateStr}, Feedback: {feedbackStr}");
|
|
||||||
NavigationAPI.navigation_free_feedback(ref feedback);
|
|
||||||
}
|
|
||||||
|
|
||||||
IntPtr fFrameId = Marshal.StringToHGlobalAnsi("fscan");
|
IntPtr fFrameId = Marshal.StringToHGlobalAnsi("fscan");
|
||||||
NavigationAPI.Header fscanHeader = NavigationAPI.header_create(Marshal.PtrToStringAnsi(fFrameId));
|
NavigationAPI.Header fscanHeader = NavigationAPI.header_create(Marshal.PtrToStringAnsi(fFrameId));
|
||||||
@@ -650,8 +660,7 @@ namespace NavigationExample
|
|||||||
NavigationAPI.navigation_add_odometry(navHandle, "odometry", odometryHandle);
|
NavigationAPI.navigation_add_odometry(navHandle, "odometry", odometryHandle);
|
||||||
|
|
||||||
// Add static map: đọc maze.yaml rồi load ảnh và cập nhật mapMetaData
|
// Add static map: đọc maze.yaml rồi load ảnh và cập nhật mapMetaData
|
||||||
string mapYamlPath = args.Length > 0 ? args[0] : Path.Combine(
|
string mapYamlPath = "maze.yaml";
|
||||||
"/home/robotics/AGV/Diff_Wheel_Prj/t800_v2_ws/src/Managerments/maps/maze", "maze.yaml");
|
|
||||||
int mapWidth, mapHeight;
|
int mapWidth, mapHeight;
|
||||||
byte[] data;
|
byte[] data;
|
||||||
MazeMapConfig mapConfig;
|
MazeMapConfig mapConfig;
|
||||||
@@ -715,8 +724,6 @@ namespace NavigationExample
|
|||||||
|
|
||||||
NavigationAPI.navigation_add_static_map(navHandle, "/map", occupancyGrid);
|
NavigationAPI.navigation_add_static_map(navHandle, "/map", occupancyGrid);
|
||||||
|
|
||||||
System.Threading.Thread.Sleep(500);
|
|
||||||
|
|
||||||
NavigationAPI.Twist2DStamped twist = new NavigationAPI.Twist2DStamped();
|
NavigationAPI.Twist2DStamped twist = new NavigationAPI.Twist2DStamped();
|
||||||
if (NavigationAPI.navigation_get_twist(navHandle, ref twist))
|
if (NavigationAPI.navigation_get_twist(navHandle, ref twist))
|
||||||
{
|
{
|
||||||
|
|||||||
Binary file not shown.
BIN
examples/NavigationExample/maze.png
Normal file
BIN
examples/NavigationExample/maze.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 2.5 KiB |
6
examples/NavigationExample/maze.yaml
Normal file
6
examples/NavigationExample/maze.yaml
Normal file
@@ -0,0 +1,6 @@
|
|||||||
|
image: maze.png
|
||||||
|
resolution: 0.05
|
||||||
|
origin: [0.0, 0.0, 0.0]
|
||||||
|
negate: 0
|
||||||
|
occupied_thresh: 0.65
|
||||||
|
free_thresh: 0.196
|
||||||
@@ -143,7 +143,6 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::GoStraight::calculator(
|
|||||||
lookahead_dist = sqrt(carrot_pose.pose.y *carrot_pose.pose.y + lookahead_dist * lookahead_dist);
|
lookahead_dist = sqrt(carrot_pose.pose.y *carrot_pose.pose.y + lookahead_dist * lookahead_dist);
|
||||||
}
|
}
|
||||||
robot_nav_2d_msgs::Twist2D drive_target;
|
robot_nav_2d_msgs::Twist2D drive_target;
|
||||||
robot::log_info_at(__FILE__, __LINE__, "y: %f theta: %f", transformed_plan.poses.front().pose.y, transformed_plan.poses.front().pose.theta);
|
|
||||||
transformed_plan = this->generateTrajectory(transformed_plan, drive_cmd, velocity, sign_x, drive_target);
|
transformed_plan = this->generateTrajectory(transformed_plan, drive_cmd, velocity, sign_x, drive_target);
|
||||||
carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan);
|
carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan);
|
||||||
|
|
||||||
|
|||||||
@@ -157,6 +157,15 @@ namespace robot_nav_core_adapter
|
|||||||
robot::log_error_at(__FILE__, __LINE__, "Failed to load planner %s", planner_name.c_str());
|
robot::log_error_at(__FILE__, __LINE__, "Failed to load planner %s", planner_name.c_str());
|
||||||
throw std::runtime_error("Failed to load planner " + planner_name);
|
throw std::runtime_error("Failed to load planner " + planner_name);
|
||||||
}
|
}
|
||||||
|
if(tf_ == nullptr)
|
||||||
|
{
|
||||||
|
robot::log_error("[%s:%d]\n ERROR: tf is nullptr", __FILE__, __LINE__);
|
||||||
|
throw std::runtime_error("Failed to create the tf");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
robot::log_info("[%s:%d]\n INFO: tf is not nullptr", __FILE__, __LINE__);
|
||||||
|
}
|
||||||
new_planner->initialize(private_nh_, planner_name, tf_, costmap_robot_);
|
new_planner->initialize(private_nh_, planner_name, tf_, costmap_robot_);
|
||||||
planner_ = new_planner;
|
planner_ = new_planner;
|
||||||
planner_loader_ = new_loader;
|
planner_loader_ = new_loader;
|
||||||
|
|||||||
Reference in New Issue
Block a user