1 Star 0 Fork 16

Xinzhi.Lin / RosSharp

加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
克隆/下载
贡献代码
同步代码
取消
提示: 由于 Git 不支持空文件夾,创建文件夹后会生成空的 .keep 文件
Loading...
README
BSD-2-Clause

博客地址:(https://www.cnblogs.com/zjwno1/p/14085226.html)

本代码是基于uml-robotics的ROS.NET修改的 改善了Service服务端与客户端通信的数据问题,并修改成多平台使用 包括了 .netcore 3.0、.netcore 3.1 、.net5 、.netframework 4.0 、.netframework 4.5 、.netframework 4.6

ROS.Sharp是什么

ROS.Sharp是一款用C#开发ROS的库 我们可以使用这个库编写订阅者和发布者,Serice客户端和Service服务端,以及参数服务器操作。

如何使用

Install-Package ROS.Sharp -Version 1.1.0 

1.发布者

class Program
{
    static Thread thread;
    static void Main(string[] args)
    {
        ROS.ROS_MASTER_URI = "http://192.168.20.132:11311";
        ROS.ROS_HOSTNAME = "192.168.20.1";
        ROS.ROS_IP = "192.168.20.132";

        string nodeName = "bbb";
        ROS.Init(nodeName);
        NodeHandle nh = new NodeHandle();
        Publisher<Messages.std_msgs.String> pub = nh.Advertise<Messages.std_msgs.String>("/chatter", 1, false);
        thread = new Thread(() =>
        {
            int i = 0;
            while (ROS.ok)
            {
                i++;
                pub.Publish(new Messages.std_msgs.String { data = "Message" + i });
                if (i == 65536)
                    i = 0;
                Thread.Sleep(1000);
            }
        });
        thread.Start();
        Console.CancelKeyPress += Console_CancelKeyPress;
    }

    private static void Console_CancelKeyPress(object sender, ConsoleCancelEventArgs e)
    {
        ROS.Shutdown();
        ROS.WaitForShutdown();
    }
}

2.订阅者

class Program
{
    static void Main(string[] args)
    {
        ROS.ROS_MASTER_URI = "http://192.168.20.132:11311";
        ROS.ROS_HOSTNAME = "192.168.20.1";
        ROS.ROS_IP = "192.168.20.132";

        string nodeName = "aaa";
        ROS.Init(nodeName);
        NodeHandle nh = new NodeHandle();
        Subscriber<Messages.std_msgs.String> sub = nh.Subscribe<Messages.std_msgs.String>("/chatter", 10, subCallback);
        Console.CancelKeyPress += Console_CancelKeyPress;
    }

    private static void Console_CancelKeyPress(object sender, ConsoleCancelEventArgs e)
    {
        ROS.Shutdown();
        ROS.WaitForShutdown();
    }

    private static void subCallback(Messages.std_msgs.String argument)
    {
        Console.WriteLine(argument.data);
    }
}

3.服务服务端

class Program
{
    static void Main(string[] args)
    {
        ROS.ROS_MASTER_URI = "http://192.168.20.132:11311";
        ROS.ROS_HOSTNAME = "192.168.20.1";
        ROS.ROS_IP = "192.168.20.132";
        ROS.Init("ServiceServerTest");
        NodeHandle nodeHandle = new NodeHandle();
        ServiceServer server = nodeHandle.AdvertiseService<TwoInts.Request, TwoInts.Response>("/add_two_ints", addition);
        Console.CancelKeyPress += Console_CancelKeyPress;
    }

    private static bool addition(TwoInts.Request req, ref TwoInts.Response resp)
    {
        resp.sum = req.a + req.b;
        return true;
    }

    private static void Console_CancelKeyPress(object sender, ConsoleCancelEventArgs e)
    {
        ROS.Shutdown();
    }
}

4.服务客户端

class Program
{
    static void Main(string[] args)
    {
        ROS.ROS_MASTER_URI = "http://192.168.20.132:11311";
        ROS.ROS_HOSTNAME = "192.168.20.1";
        ROS.ROS_IP = "192.168.20.132";
        ROS.Init("ServiceClientTest");
        NodeHandle nodeHandle = new NodeHandle();
        new Thread(new ThreadStart(() =>
        {
            Random r = new Random();
            while (ROS.ok)
            {
                try
                {
                    TwoInts.Request req = new TwoInts.Request() { a = r.Next(100), b = r.Next(100) };
                    TwoInts.Response resp = new TwoInts.Response();
                    DateTime before = DateTime.Now;
                    bool res = nodeHandle.ServiceClient<TwoInts.Request, TwoInts.Response>("/add_two_ints").Call(req, ref resp);
                    TimeSpan dif = DateTime.Now.Subtract(before);

                    string str = "";
                    if (res)
                        str = "" + req.a + " + " + req.b + " = " + resp.sum + "\n";
                    else
                        str = "call failed after\n";
                    str += Math.Round(dif.TotalMilliseconds, 2) + " ms";
                    Console.WriteLine(str);
                }
                catch
                {

                }
                Thread.Sleep(500);
            }
        })).Start();
        Console.CancelKeyPress += Console_CancelKeyPress;
    }

    private static void Console_CancelKeyPress(object sender, ConsoleCancelEventArgs e)
    {
        ROS.Shutdown();
    }
}

5.参数服务器

class Program
{
    static void Main(string[] args)
    {
        ROS.ROS_MASTER_URI = "http://192.168.20.132:11311";
        ROS.ROS_HOSTNAME = "192.168.20.1";
        ROS.ROS_IP = "192.168.20.132";
        IDictionary remappings;
        RemappingHelper.GetRemappings(out remappings);
        Network.Init(remappings);
        Master.Init(remappings);
        ThisNode.Init("", remappings, (int)(InitOption.AnonymousName | InitOption.NoRousout));
        Param.Init(remappings);
        //获得所有参数
        List<string> list = Param.List();

        foreach (string s in list)
        {
            Console.WriteLine(s);
        }
        //获取参数值
        foreach (string s in list)
        {
            bool flag = Param.Has(s);
            if (!flag)
            {
                Console.WriteLine("不存在参数{0}", s);
                continue;
            }
            object obj = Param.Get(s);
            if (obj == null)
            {
                Console.WriteLine("获取参数失败");
                continue;
            }

            Console.WriteLine("参数:{0},值:{1}", s, obj);
        }
        //设置参数值
        //Param.set(key, value);
        //Param.del(key)
        Console.ReadKey();
    }
}

6.根据msg文件和srv文件生成代码

static void Main(string[] args)
{
    string inputDir = AppDomain.CurrentDomain.BaseDirectory + "common_msgs/";
    string outputdir = AppDomain.CurrentDomain.BaseDirectory + "Messages";
    Console.WriteLine("开始生成ROS Messages...\n");
    GenerateHelper.GenerateMsgAndSrv(inputDir, outputdir);
    Console.WriteLine("生成完成");
    Console.ReadLine();
}
Copyright (c) 2014, UMass Lowell Robotics Lab All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

简介

使用NET5开发的ROS通信库,包含例子,以及msg,srv生成工具 展开 收起
C#
BSD-2-Clause
取消

发行版

暂无发行版

贡献者

全部

近期动态

加载更多
不能加载更多了
C#
1
https://gitee.com/xinzhi_git/ros-sharp.git
git@gitee.com:xinzhi_git/ros-sharp.git
xinzhi_git
ros-sharp
RosSharp
master

搜索帮助