update
This commit is contained in:
@@ -1,9 +1,24 @@
|
||||
using System;
|
||||
using System.Globalization;
|
||||
using System.IO;
|
||||
using System.Runtime.InteropServices;
|
||||
using System.Runtime.CompilerServices;
|
||||
using System.Text.RegularExpressions;
|
||||
using SixLabors.ImageSharp;
|
||||
using SixLabors.ImageSharp.PixelFormats;
|
||||
|
||||
namespace NavigationExample
|
||||
{
|
||||
/// <summary>Thông tin map đọc từ file YAML (maze.yaml).</summary>
|
||||
public struct MazeMapConfig
|
||||
{
|
||||
public string ImagePath; // đường dẫn đầy đủ tới file ảnh
|
||||
public float Resolution;
|
||||
public double OriginX, OriginY, OriginZ;
|
||||
public int Negate; // 0 hoặc 1
|
||||
public double OccupiedThresh;
|
||||
public double FreeThresh;
|
||||
}
|
||||
/// <summary>
|
||||
/// C# P/Invoke wrapper for Navigation C API
|
||||
/// </summary>
|
||||
@@ -308,7 +323,7 @@ namespace NavigationExample
|
||||
|
||||
[DllImport(DllName, CallingConvention = CallingConvention.Cdecl, CharSet = CharSet.Ansi)]
|
||||
[return: MarshalAs(UnmanagedType.I1)]
|
||||
public static extern bool navigation_move_straight_to(NavigationHandle handle, PoseStamped goal, double xy_goal_tolerance);
|
||||
public static extern bool navigation_move_straight_to(NavigationHandle handle, double distance);
|
||||
|
||||
[DllImport(DllName, CallingConvention = CallingConvention.Cdecl, CharSet = CharSet.Ansi)]
|
||||
[return: MarshalAs(UnmanagedType.I1)]
|
||||
@@ -370,6 +385,105 @@ namespace NavigationExample
|
||||
// ============================================================================
|
||||
class Program
|
||||
{
|
||||
/// <summary>
|
||||
/// Đọc file maze.yaml (image, resolution, origin, negate, occupied_thresh, free_thresh).
|
||||
/// ImagePath được resolve tuyệt đối theo thư mục chứa file yaml.
|
||||
/// </summary>
|
||||
static bool TryLoadMazeYaml(string yamlPath, out MazeMapConfig config)
|
||||
{
|
||||
config = default;
|
||||
if (string.IsNullOrEmpty(yamlPath) || !File.Exists(yamlPath))
|
||||
return false;
|
||||
string dir = Path.GetDirectoryName(Path.GetFullPath(yamlPath)) ?? "";
|
||||
try
|
||||
{
|
||||
string[] lines = File.ReadAllLines(yamlPath);
|
||||
foreach (string line in lines)
|
||||
{
|
||||
string trimmed = line.Trim();
|
||||
if (trimmed.Length == 0 || trimmed.StartsWith("#")) continue;
|
||||
int colon = trimmed.IndexOf(':');
|
||||
if (colon <= 0) continue;
|
||||
string key = trimmed.Substring(0, colon).Trim();
|
||||
string value = trimmed.Substring(colon + 1).Trim();
|
||||
if (key == "image")
|
||||
config.ImagePath = Path.Combine(dir, value);
|
||||
else if (key == "resolution" && float.TryParse(value, NumberStyles.Float, CultureInfo.InvariantCulture, out float res))
|
||||
config.Resolution = res;
|
||||
else if (key == "origin")
|
||||
{
|
||||
var m = Regex.Match(value, @"\[\s*([-\d.]+\s*),\s*([-\d.]+\s*),\s*([-\d.]+)\s*\]");
|
||||
if (m.Success)
|
||||
{
|
||||
config.OriginX = double.Parse(m.Groups[1].Value, CultureInfo.InvariantCulture);
|
||||
config.OriginY = double.Parse(m.Groups[2].Value, CultureInfo.InvariantCulture);
|
||||
config.OriginZ = double.Parse(m.Groups[3].Value, CultureInfo.InvariantCulture);
|
||||
}
|
||||
}
|
||||
else if (key == "negate" && int.TryParse(value, out int neg))
|
||||
config.Negate = neg;
|
||||
else if (key == "occupied_thresh" && double.TryParse(value, NumberStyles.Float, CultureInfo.InvariantCulture, out double ot))
|
||||
config.OccupiedThresh = ot;
|
||||
else if (key == "free_thresh" && double.TryParse(value, NumberStyles.Float, CultureInfo.InvariantCulture, out double ft))
|
||||
config.FreeThresh = ft;
|
||||
}
|
||||
return !string.IsNullOrEmpty(config.ImagePath);
|
||||
}
|
||||
catch
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Đọc file ảnh PNG và chuyển pixel sang byte[] occupancy (0=free, 100=occupied, 255=unknown).
|
||||
/// Dùng negate, occupied_thresh, free_thresh từ maze.yaml nếu cung cấp.
|
||||
/// </summary>
|
||||
static byte[] LoadMazePixelsAsOccupancy(string imagePath, out int width, out int height,
|
||||
int negate = 0, double occupiedThresh = 0.65, double freeThresh = 0.196)
|
||||
{
|
||||
width = 0;
|
||||
height = 0;
|
||||
if (string.IsNullOrEmpty(imagePath) || !File.Exists(imagePath))
|
||||
{
|
||||
LogError($"File not found: {imagePath}");
|
||||
return null;
|
||||
}
|
||||
try
|
||||
{
|
||||
using var image = Image.Load<Rgba32>(imagePath);
|
||||
int w = image.Width;
|
||||
int h = image.Height;
|
||||
width = w;
|
||||
height = h;
|
||||
byte[] data = new byte[w * h];
|
||||
image.ProcessPixelRows(accessor =>
|
||||
{
|
||||
for (int y = 0; y < accessor.Height; y++)
|
||||
{
|
||||
Span<Rgba32> row = accessor.GetRowSpan(y);
|
||||
for (int x = 0; x < row.Length; x++)
|
||||
{
|
||||
ref readonly Rgba32 p = ref row[x];
|
||||
double gray = (p.R + p.G + p.B) / 255.0 / 3.0;
|
||||
if (negate != 0) gray = 1.0 - gray;
|
||||
byte occ;
|
||||
if (gray <= freeThresh) occ = 0;
|
||||
else if (gray >= occupiedThresh) occ = 100;
|
||||
else occ = 255; // unknown
|
||||
data[y * w + x] = occ;
|
||||
}
|
||||
}
|
||||
});
|
||||
return data;
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
LogError($"Load image failed: {ex.Message}");
|
||||
return null;
|
||||
}
|
||||
}
|
||||
|
||||
// Helper method để hiển thị file và line number tự động
|
||||
static void LogError(string message,
|
||||
[CallerFilePath] string filePath = "",
|
||||
@@ -459,8 +573,7 @@ namespace NavigationExample
|
||||
Console.WriteLine($"State: {stateStr}, Feedback: {feedbackStr}");
|
||||
NavigationAPI.navigation_free_feedback(ref feedback);
|
||||
}
|
||||
|
||||
System.Threading.Thread.Sleep(1000);
|
||||
|
||||
IntPtr fFrameId = Marshal.StringToHGlobalAnsi("fscan");
|
||||
NavigationAPI.Header fscanHeader = NavigationAPI.header_create(Marshal.PtrToStringAnsi(fFrameId));
|
||||
NavigationAPI.LaserScan fscanHandle;
|
||||
@@ -480,7 +593,6 @@ namespace NavigationExample
|
||||
fscanHandle.intensities_count = new UIntPtr(5);
|
||||
NavigationAPI.navigation_add_laser_scan(navHandle, "/fscan", fscanHandle);
|
||||
|
||||
|
||||
IntPtr bFrameId = Marshal.StringToHGlobalAnsi("bscan");
|
||||
NavigationAPI.Header bscanHeader = NavigationAPI.header_create(Marshal.PtrToStringAnsi(bFrameId));
|
||||
NavigationAPI.LaserScan bscanHandle;
|
||||
@@ -500,8 +612,6 @@ namespace NavigationExample
|
||||
bscanHandle.intensities_count = new UIntPtr(5);
|
||||
NavigationAPI.navigation_add_laser_scan(navHandle, "/bscan", bscanHandle);
|
||||
|
||||
System.Threading.Thread.Sleep(1000);
|
||||
|
||||
IntPtr oFrameId = Marshal.StringToHGlobalAnsi("odom");
|
||||
NavigationAPI.Header odometryHeader = NavigationAPI.header_create(Marshal.PtrToStringAnsi(oFrameId));
|
||||
NavigationAPI.Odometry odometryHandle = new NavigationAPI.Odometry();
|
||||
@@ -539,18 +649,53 @@ namespace NavigationExample
|
||||
odometryHandle.twist.covariance_count = new UIntPtr((uint)twist_covariance.Length);
|
||||
NavigationAPI.navigation_add_odometry(navHandle, "odometry", odometryHandle);
|
||||
|
||||
System.Threading.Thread.Sleep(1000);
|
||||
// Add static map
|
||||
// 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(
|
||||
"/home/robotics/AGV/Diff_Wheel_Prj/t800_v2_ws/src/Managerments/maps/maze", "maze.yaml");
|
||||
int mapWidth, mapHeight;
|
||||
byte[] data;
|
||||
MazeMapConfig mapConfig;
|
||||
if (TryLoadMazeYaml(mapYamlPath, out mapConfig))
|
||||
{
|
||||
data = LoadMazePixelsAsOccupancy(mapConfig.ImagePath, out mapWidth, out mapHeight,
|
||||
mapConfig.Negate, mapConfig.OccupiedThresh, mapConfig.FreeThresh);
|
||||
if (data == null)
|
||||
{
|
||||
mapWidth = 3;
|
||||
mapHeight = 10;
|
||||
data = new byte[30];
|
||||
for (int i = 0; i < data.Length; i++) data[i] = 100;
|
||||
Console.WriteLine("YAML loaded but image failed; using default map 3x10");
|
||||
}
|
||||
else
|
||||
{
|
||||
Console.WriteLine("Loaded map from {0}: {1}x{2}, resolution={3}, origin=({4},{5},{6})",
|
||||
mapConfig.ImagePath, mapWidth, mapHeight, mapConfig.Resolution,
|
||||
mapConfig.OriginX, mapConfig.OriginY, mapConfig.OriginZ);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
mapWidth = 3;
|
||||
mapHeight = 10;
|
||||
data = new byte[30];
|
||||
for (int i = 0; i < data.Length; i++) data[i] = 100;
|
||||
mapConfig = default;
|
||||
mapConfig.Resolution = 0.05f;
|
||||
mapConfig.OriginX = mapConfig.OriginY = mapConfig.OriginZ = 0.0;
|
||||
Console.WriteLine("maze.yaml not found, using default map 3x10");
|
||||
}
|
||||
|
||||
NavigationAPI.Time mapLoadTime = NavigationAPI.time_create();
|
||||
NavigationAPI.MapMetaData mapMetaData = new NavigationAPI.MapMetaData();
|
||||
mapMetaData.map_load_time = mapLoadTime;
|
||||
mapMetaData.resolution = 0.05f;
|
||||
mapMetaData.width = 3;
|
||||
mapMetaData.height = 10;
|
||||
mapMetaData.resolution = mapConfig.Resolution;
|
||||
mapMetaData.width = (uint)mapWidth;
|
||||
mapMetaData.height = (uint)mapHeight;
|
||||
mapMetaData.origin = new NavigationAPI.Pose();
|
||||
mapMetaData.origin.position.x = 0.0;
|
||||
mapMetaData.origin.position.y = 0.0;
|
||||
mapMetaData.origin.position.z = 0.0;
|
||||
mapMetaData.origin.position.x = mapConfig.OriginX;
|
||||
mapMetaData.origin.position.y = mapConfig.OriginY;
|
||||
mapMetaData.origin.position.z = mapConfig.OriginZ;
|
||||
mapMetaData.origin.orientation.x = 0.0;
|
||||
mapMetaData.origin.orientation.y = 0.0;
|
||||
mapMetaData.origin.orientation.z = 0.0;
|
||||
@@ -559,10 +704,6 @@ namespace NavigationExample
|
||||
IntPtr mapFrameId = Marshal.StringToHGlobalAnsi("map");
|
||||
occupancyGrid.header = NavigationAPI.header_create(Marshal.PtrToStringAnsi(mapFrameId));
|
||||
occupancyGrid.info = mapMetaData;
|
||||
byte[] data = new byte[30];
|
||||
for (int i = 0; i < data.Length; i++) {
|
||||
data[i] = 100;
|
||||
}
|
||||
occupancyGrid.data = Marshal.AllocHGlobal(sizeof(byte) * data.Length);
|
||||
Marshal.Copy(data, 0, occupancyGrid.data, data.Length);
|
||||
occupancyGrid.data_count = new UIntPtr((uint)data.Length);
|
||||
@@ -574,7 +715,7 @@ namespace NavigationExample
|
||||
|
||||
NavigationAPI.navigation_add_static_map(navHandle, "/map", occupancyGrid);
|
||||
|
||||
System.Threading.Thread.Sleep(1000);
|
||||
System.Threading.Thread.Sleep(500);
|
||||
|
||||
NavigationAPI.Twist2DStamped twist = new NavigationAPI.Twist2DStamped();
|
||||
if (NavigationAPI.navigation_get_twist(navHandle, ref twist))
|
||||
@@ -584,8 +725,12 @@ namespace NavigationExample
|
||||
NavigationAPI.MarshalString(twist.header.frame_id), twist.velocity.x, twist.velocity.y, twist.velocity.theta);
|
||||
}
|
||||
// Cleanup
|
||||
NavigationAPI.navigation_move_straight_to(navHandle, 1.0);
|
||||
|
||||
NavigationAPI.navigation_destroy(navHandle);
|
||||
NavigationAPI.tf_listener_destroy(tfHandle);
|
||||
Console.WriteLine("Press any key to exit...");
|
||||
Console.ReadKey();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user