ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

Hello,

When you use roslibjs with rosbridge, your website is not a node, but it can be seen as a node (it just don't register with the rosmaster, so you can't see him with "rosnode list"). Rosbridge act as a proxy to use ROS functionnalities.

The easiest way to launch a remote process from your website is to use a process management library like std::system, boost::process or POCO , there are all available in ROS (POCO need this)

For an example with std::system :

#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>

    void callback(std_msgs::String msg){
        std::stringstream ss;
        ss << "roslaunch " << msg.data;
        std::system(ss.str().c_str());//std::system only accept c_str() a.k.a char*
    }

    int main(int argc, char** argv){
        ros::init(argc,argv,"roslaunch_launcher");
        ros::NodeHandle n;
        ros::Subscriber sub = n.subscribe("/launch", 1, callback);
        ros::spin();
        return 0;
    }

Just publish a string in the form "< package name > < launch file name >" and the launch file should be called

You also should be sure to source the correct environment BEFORE launch this node, if you try to launch a file from an another workspace (not sourced) or you create a package after launching this node, the loaded environmnent will not find the launch file.

Hello,

When you use roslibjs with rosbridge, your website is not a node, but it can be seen as a node (it just don't register with the rosmaster, so you can't see him with "rosnode list"). Rosbridge act as a proxy to use ROS functionnalities.

The easiest way to launch a remote process from your website is to use a process management library like std::system, boost::process or POCO , there are all available in ROS (POCO need this)

For an example with std::system : (will quit the callback only when the process finish):

#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>

    void callback(std_msgs::String msg){
        std::stringstream ss;
        ss << "roslaunch " << msg.data;
        std::system(ss.str().c_str());//std::system only accept c_str() a.k.a char*
    }

    int main(int argc, char** argv){
        ros::init(argc,argv,"roslaunch_launcher");
        ros::NodeHandle n;
        ros::Subscriber sub = n.subscribe("/launch", 1, callback);
        ros::spin();
        return 0;
    }

Just publish a string in the form "< package name > < launch file name >" and the launch file should be called

You also should be sure to source the correct environment BEFORE launch this node, if you try to launch a file from an another workspace (not sourced) or you create a package after launching this node, the loaded environmnent will not find the launch file.

And an example with POCO (with a run/kill procedure):

#include <ros/ros.h>
#include <std_msgs/String.h>
#include <std_msgs/Empty.h>
#include "Poco/Process.h"
#include <boost/algorithm/string/classification.hpp>
#include <boost/algorithm/string/split.hpp>


Poco::ProcessHandle* ph;
bool running = false;

void callback_run(std_msgs::String msg){
    if(!running){
        std::vector<std::string> args;
        boost::split(args, msg.data, boost::is_any_of(" ") );
        Poco::ProcessHandle ph_running = Poco::Process::launch("rosrun", args,0,0,0);
        ph = new Poco::ProcessHandle(ph_running);
        running = true;
        ROS_INFO_STREAM("launched : rosrun " << msg.data);
    }
    else{
        ROS_ERROR("A process is already running.");
    }
}

void callback_kill(std_msgs::Empty msg){
    if(running){
        Poco::Process::kill(ph->id());
        free(ph);
        running = false;
        ROS_INFO("Killed process");
    }
    else{
        ROS_ERROR("No Process are running.");
    }
}


int main(int argc, char** argv){
    ros::init(argc, argv, "node_runner");
    ros::NodeHandle n;
    ros::Subscriber sub_run = n.subscribe("/run",100,callback_run);
    ros::Subscriber sub_kill = n.subscribe("/kill",100,callback_kill);
    ros::spin();
    return 0;
}

This example subscribe 2 topics : /run and /kill. Run will accept a node package a name (example : 'rqt_gui rqt_gui') and kill accept a std_msgs/Empty.

This need a little work, as the std::system example will block the subscriber (the function return only when the process die) and the POCO example will not accept roslaunch , even if the roslaunch is killed, the subprocess are still running.

Hello,

When you use roslibjs with rosbridge, your website is not a node, but it can be seen as a node (it just don't register with the rosmaster, so you can't see him with "rosnode list"). Rosbridge act as a proxy to use ROS functionnalities.

The easiest way to launch a remote process from your website is to use a process management library like std::system, boost::process or POCO , there are all available in ROS (POCO need this)

For an example with std::system (will quit the callback only when the process finish):

#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>

    void callback(std_msgs::String msg){
        std::stringstream ss;
        ss << "roslaunch " << msg.data;
        std::system(ss.str().c_str());//std::system only accept c_str() a.k.a char*
    }

    int main(int argc, char** argv){
        ros::init(argc,argv,"roslaunch_launcher");
        ros::NodeHandle n;
        ros::Subscriber sub = n.subscribe("/launch", 1, callback);
        ros::spin();
        return 0;
    }

Just publish a string in the form "< package name > < launch file name >" and the launch file should be called

You also should be sure to source the correct environment BEFORE launch this node, if you try to launch a file from an another workspace (not sourced) or you create a package after launching this node, the loaded environmnent will not find the launch file.

And an example with POCO (with a run/kill procedure):

#include <ros/ros.h>
#include <std_msgs/String.h>
#include <std_msgs/Empty.h>
#include "Poco/Process.h"
#include <boost/algorithm/string/classification.hpp>
#include <boost/algorithm/string/split.hpp>


Poco::ProcessHandle* ph;
bool running = false;

void callback_run(std_msgs::String msg){
    if(!running){
        std::vector<std::string> args;
        boost::split(args, msg.data, boost::is_any_of(" ") );
); //Split the msg.data on space and save it to a vector
        Poco::ProcessHandle ph_running = Poco::Process::launch("rosrun", args,0,0,0);
args,0,0,0); //launch a new node
        ph = new Poco::ProcessHandle(ph_running);
Poco::ProcessHandle(ph_running); // Copy the processhandler to our global variable
        running = true;
true; //Refuse new launch
        ROS_INFO_STREAM("launched : rosrun " roslaunch" << msg.data);
    }
    else{
        ROS_ERROR("A process is already running.");
    }
}

void callback_kill(std_msgs::Empty msg){
    if(running){
        Poco::Process::kill(ph->id());
        free(ph);
Poco::Process::requestTermination(ph->id()); //send SIGINT
            Poco::Process::wait(*ph); //Wait for roslaunch to kill every node
        free(ph);  
        running = false;
false;  //accept a new launch
        ROS_INFO("Killed process");
    }
    else{
        ROS_ERROR("No Process are running.");
    }
}


int main(int argc, char** argv){
    ros::init(argc, argv, "node_runner");
    ros::NodeHandle n;
    ros::Subscriber sub_run = n.subscribe("/run",100,callback_run);
    ros::Subscriber sub_kill = n.subscribe("/kill",100,callback_kill);
    ros::spin();
    return 0;
}

This example subscribe 2 topics : /run and /kill. Run will accept a node package a name (example : 'rqt_gui rqt_gui') and kill accept a std_msgs/Empty.

This need a little work, as the std::system example will block the subscriber (the function return only when the process die) and the POCO example will not accept roslaunch , even if the roslaunch is killed, the subprocess are still running.

can launch only a single node

Hello,

When you use roslibjs with rosbridge, your website is not a node, but it can be seen as a node (it just don't register with the rosmaster, so you can't see him with "rosnode list"). Rosbridge act as a proxy to use ROS functionnalities.

The easiest way to launch a remote process from your website is to use a process management library like std::system, boost::process or POCO , there are all available in ROS (POCO need this)

For an example with std::system (will quit the callback only when the process finish):

#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>

    void callback(std_msgs::String msg){
        std::stringstream ss;
        ss << "roslaunch " << msg.data;
        std::system(ss.str().c_str());//std::system only accept c_str() a.k.a char*
    }

    int main(int argc, char** argv){
        ros::init(argc,argv,"roslaunch_launcher");
        ros::NodeHandle n;
        ros::Subscriber sub = n.subscribe("/launch", 1, callback);
        ros::spin();
        return 0;
    }

Just publish a string in the form "< package name > < launch file name >" and the launch file should be called

You also should be sure to source the correct environment BEFORE launch this node, if you try to launch a file from an another workspace (not sourced) or you create a package after launching this node, the loaded environmnent will not find the launch file.

And an example with POCO (with a run/kill procedure):

#include <ros/ros.h>
#include <std_msgs/String.h>
#include <std_msgs/Empty.h>
#include "Poco/Process.h"
#include <boost/algorithm/string/classification.hpp>
#include <boost/algorithm/string/split.hpp>


Poco::ProcessHandle* ph;
bool running = false;

void callback_run(std_msgs::String msg){
    if(!running){
        std::vector<std::string> args;
        boost::split(args, msg.data, boost::is_any_of(" ") ); //Split the msg.data on space and save it to a vector
        Poco::ProcessHandle ph_running = Poco::Process::launch("rosrun", Poco::Process::launch("roslaunch", args,0,0,0); //launch a new node
        ph = new Poco::ProcessHandle(ph_running); // Copy the processhandler to our global variable
        running = true; //Refuse new launch
        ROS_INFO_STREAM("launched : roslaunch" << msg.data);
    }
    else{
        ROS_ERROR("A process is already running.");
    }
}

void callback_kill(std_msgs::Empty msg){
    if(running){
        Poco::Process::requestTermination(ph->id()); //send SIGINT
            Poco::Process::wait(*ph); //Wait for roslaunch to kill every node
        free(ph);  
        running = false;  //accept a new launch
        ROS_INFO("Killed process");
    }
    else{
        ROS_ERROR("No Process are running.");
    }
}


int main(int argc, char** argv){
    ros::init(argc, argv, "node_runner");
    ros::NodeHandle n;
    ros::Subscriber sub_run = n.subscribe("/run",100,callback_run);
    ros::Subscriber sub_kill = n.subscribe("/kill",100,callback_kill);
    ros::spin();
    return 0;
}

This example subscribe 2 topics : /run and /kill. Run will accept a node package a name (example : 'rqt_gui rqt_gui') and kill accept a std_msgs/Empty.

This need a little work, as the std::system example will block the subscriber (the function return only when the process die) and the POCO example can launch only a single node

die).