Module: Orocos::ROS
- Extended by:
- Logger::Hierarchy
- Defined in:
- lib/orocos/ros.rb,
lib/orocos/ros/rpc.rb,
lib/orocos/ros/base.rb,
lib/orocos/ros/node.rb,
lib/orocos/ros/topic.rb,
lib/orocos/ros/name_service.rb,
lib/orocos/ros/name_mappings.rb,
lib/orocos/ros/process_manager.rb,
ext/rorocos/ros.cc
Defined Under Namespace
Classes: ComError, DefaultLoader, InputTopic, LauncherProcess, NameMappings, NameService, Node, NodeGraph, OutputTopic, ProcessManager, ROSMaster, ROSSlave, ROS_XMLRPC, Topic
Class Attribute Summary collapse
-
.caller_id ⇒ Object
The caller ID for this process.
Class Method Summary collapse
- .available? ⇒ Boolean
- .clear ⇒ Object
- .default_loader ⇒ Object
- .default_ros_master_uri ⇒ Object
- .disable ⇒ Object
- .do_initialize(, mod) ⇒ Object
- .enabled? ⇒ Boolean
- .initialize(name = ROS.caller_id[1..-1]) ⇒ Object
- .initialized? ⇒ Boolean
-
.load ⇒ Object
Helper method for initialize.
- .loaded? ⇒ Boolean
-
.map_message_type_to_orogen(message_type) ⇒ String
The type name that should be used on the oroGen side to represent the given ROS message.
-
.name_service ⇒ NameService, false
Returns the ROS name service that gives access to the master listed in ROS_MASTER_URI.
-
.ros_master ⇒ Object
The global ROS master as a XMLRPC object.
-
.ros_master_uri ⇒ Object
Returns the URI to the ROS master.
-
.roscore_available? ⇒ Boolean
Test whether roscore is available or not.
-
.roscore_pid ⇒ Int
Get the roscore process id.
-
.roscore_shutdown ⇒ Boolean
Shutdown roscore if controlled by this process, otherwise calls to this function will return false This will only work if roscore has been started by the same ruby process.
-
.roscore_start(*args) ⇒ Object
Start the roscore process @return Pid of the roscore process see #roscore_pid.
-
.roslaunch(package_name, launch_name, options = Hash.new) ⇒ Int
Run the launch from the package
package_name
given bylaunch_name
. - .shutdown ⇒ Object
-
.topic(name) ⇒ Object
Resolves an existing topic by name.
Class Attribute Details
.caller_id ⇒ Object
The caller ID for this process. Defaults to orocosrb_<pid>
5 6 7 |
# File 'lib/orocos/ros/rpc.rb', line 5 def caller_id @caller_id end |
Class Method Details
.available? ⇒ Boolean
5 6 7 8 9 10 |
# File 'lib/orocos/ros.rb', line 5 def self.available? if @available.nil? @available = defined? TRANSPORT_ROS end @available end |
.clear ⇒ Object
33 34 35 36 |
# File 'lib/orocos/ros/base.rb', line 33 def self.clear default_loader.clear @loaded = false end |
.default_loader ⇒ Object
21 22 23 24 |
# File 'lib/orocos/ros/base.rb', line 21 def self.default_loader Orocos.default_loader @default_loader ||= DefaultLoader.new(Orocos.default_loader) end |
.default_ros_master_uri ⇒ Object
39 40 41 |
# File 'lib/orocos/ros.rb', line 39 def self.default_ros_master_uri ENV['ROS_MASTER_URI'] end |
.disable ⇒ Object
11 12 13 |
# File 'lib/orocos/ros.rb', line 11 def self.disable @enabled = false end |
.do_initialize(, mod) ⇒ Object
12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 |
# File 'ext/rorocos/ros.cc', line 12
static VALUE ros_init(int argc, VALUE* _argv, VALUE mod)
{
VALUE name, rest;
rb_scan_args(argc, _argv, "1*", &name, &rest);
size_t size = RARRAY_LEN(rest);
std::vector<char const*> argv;
argv.resize(size + 1);
argv[0] = "";
for (int i = 0; i < size; ++i)
{
VALUE element = RARRAY_PTR(rest)[i];
argv[i + 1] = StringValuePtr(element);
}
if(!ros::isInitialized()){
int argc = 0;
ros::init(argc,NULL,StringValuePtr(name), ros::init_options::NoSigintHandler | ros::init_options::NoRosout);
if(ros::master::check())
ros::start();
else{
rb_raise(eROSComError, "cannot communicate with ROS master");
}
}
static ros::AsyncSpinner spinner(1); // Use 1 threads
spinner.start();
return Qnil;
}
|
.enabled? ⇒ Boolean
14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 |
# File 'lib/orocos/ros.rb', line 14 def self.enabled? if @enabled == false return false elsif available? && (ENV['ROCK_ROS_INTEGRATION'] != '0') return false if !ENV['ROS_MASTER_URI'] if @enabled.nil? # This is getting automatically enabled, check if it is # actually available begin Orocos::ROS.name_service Orocos.default_cmdline_arguments = Orocos.default_cmdline_arguments.merge('with-ros' => true) Orocos.debug "ROS integration was enabled, passing default arguments: #{Orocos.default_cmdline_arguments}" @enabled = true rescue Orocos::ROS::ComError Orocos.warn "ROS integration was enabled, but I cannot contact the ROS master at #{Orocos::ROS.default_ros_master_uri}, disabling" Orocos::ROS.disable Orocos.default_cmdline_arguments = Orocos.default_cmdline_arguments.delete('with-ros') @enabled = false end end @enabled end end |
.initialize(name = ROS.caller_id[1..-1]) ⇒ Object
21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 |
# File 'lib/orocos/ros/rpc.rb', line 21 def self.initialize(name = ROS.caller_id[1..-1]) if initialized? raise RuntimeError, "cannot initialize the ROS layer multiple times" end ROS.load do_initialize(name) at_exit do if ROS.initialized? ROS.shutdown end end end |
.initialized? ⇒ Boolean
7 8 9 10 |
# File 'ext/rorocos/ros.cc', line 7
static VALUE ros_is_initialized(VALUE mod)
{
return ros::isInitialized() ? Qtrue : Qfalse;
}
|
.load ⇒ Object
Helper method for initialize
27 28 29 |
# File 'lib/orocos/ros/base.rb', line 27 def self.load @loaded = true end |
.loaded? ⇒ Boolean
31 |
# File 'lib/orocos/ros/base.rb', line 31 def self.loaded?; !!@loaded end |
.map_message_type_to_orogen(message_type) ⇒ String
Returns the type name that should be used on the oroGen side to represent the given ROS message
7 8 9 |
# File 'lib/orocos/ros/base.rb', line 7 def self.() default_loader.() end |
.name_service ⇒ NameService, false
Returns the ROS name service that gives access to the master listed in ROS_MASTER_URI
48 49 50 51 52 53 54 55 56 |
# File 'lib/orocos/ros.rb', line 48 def self.name_service if @name_service return @name_service else ns = Orocos::ROS::NameService.new ns.validate @name_service = ns end end |
.ros_master ⇒ Object
The global ROS master as a XMLRPC object
It gets initialized on first call
15 16 17 |
# File 'lib/orocos/ros/rpc.rb', line 15 def self.ros_master @ros_master ||= XMLRPC::Client::Proxy.new(ros_master_uri, '') end |
.ros_master_uri ⇒ Object
Returns the URI to the ROS master
7 8 9 |
# File 'lib/orocos/ros/rpc.rb', line 7 def self.ros_master_uri ENV['ROS_MASTER_URI'] end |
.roscore_available? ⇒ Boolean
Test whether roscore is available or not
47 48 49 50 51 52 53 |
# File 'lib/orocos/ros/base.rb', line 47 def self.roscore_available? begin !rosnode_list.empty? rescue InternalError => e false end end |
.roscore_pid ⇒ Int
Get the roscore process id
41 42 43 |
# File 'lib/orocos/ros/base.rb', line 41 def self.roscore_pid @roscore_pid || 0 end |
.roscore_shutdown ⇒ Boolean
Shutdown roscore if controlled by this process, otherwise calls to this function will return false This will only work if roscore has been started by the same ruby process
86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 |
# File 'lib/orocos/ros/base.rb', line 86 def self.roscore_shutdown begin if @roscore_pid info "roscore will be shutdown" status = ::Process.kill('INT',@roscore_pid) @roscore_pid = nil return status end rescue Errno::ESRCH raise ArgumentError, "trying to shutdown roscore, which is not running anymore with pid '#{@roscore_pid}'" end warn "roscore is not controlled by this process; no shutdown will be performed" false end |
.roscore_start(*args) ⇒ Object
Start the roscore process @return Pid of the roscore process see #roscore_pid
57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 |
# File 'lib/orocos/ros/base.rb', line 57 def self.roscore_start(*args) = args.last.kind_of?(Hash) ? args.pop : Hash.new , = Kernel. , :redirect => File.join("/var/tmp/roscore.log") args << if !roscore_available? @roscore_pid = Utilrb.spawn "roscore", *args ::Process.detach(@roscore_pid) @roscore_pid elsif !@roscore_pid warn "roscore is already running, but is not controlled by this process" else info "roscore is already running, pid '#{@roscore_pid}'" end if [:wait] while !roscore_available? sleep 0.1 end end end |
.roslaunch(package_name, launch_name, options = Hash.new) ⇒ Int
Run the launch from the package package_name
given by
launch_name
108 109 110 111 112 113 114 115 116 |
# File 'lib/orocos/ros/base.rb', line 108 def self.roslaunch(package_name, launch_name, = Hash.new) launch_name = launch_name.gsub(/\.launch/,'') launch_name = launch_name + ".launch" arguments = [package_name, launch_name] arguments += [] pid = Utilrb.spawn "roslaunch", "__name:=#{launch_name}", *arguments pid end |
.shutdown ⇒ Object
42 43 44 45 46 |
# File 'ext/rorocos/ros.cc', line 42
static VALUE ros_shutdown()
{
ros::shutdown();
return Qnil;
}
|
.topic(name) ⇒ Object
Resolves an existing topic by name
183 184 185 186 187 188 189 190 191 192 |
# File 'lib/orocos/ros/topic.rb', line 183 def self.topic(name) Orocos.name_service.each do |ns| if ns.respond_to?(:find_topic_by_name) if topic = ns.find_topic_by_name(name) return topic end end end raise NotFound, "topic #{name} does not seem to exist" end |