failed to spawn a model by calling service
Hi everyone
I try to spawn a hector quadrotor model in c++ file as a ros node. But it always return "failed to call the service". I attached my code below:
#include "ros/ros.h"
#include <geometry_msgs pose.h="">
#include <gazebo_msgs spawnmodel.h="">
#include <stdlib.h>
#include<iostream>
#include<fstream>
#include <tf transform_datatypes.h>
int main(int argc, char **argv) { ros::init(argc, argv, "commander"); // Node setup ros::NodeHandle nh;
std::ifstream ifs;
ifs.open("quadrotor_hokuyo_utm30lx.gazebo.xacro");
ros::ServiceClient spawn = nh.serviceClient< gazebo_msgs::SpawnModel> ("/gazebo/spawn_urdf_model");
gazebo_msgs::SpawnModel s1;
geometry_msgs::Pose p1;
s1.request.model_name = "uav3";
ifs >> s1.request.model_xml;
s1.request.robot_namespace = "uav3";
p1.position.x = 2.0;
p1.position.y = 2.0;
p1.position.z = 0.0;
p1.orientation = tf::createQuaternionMsgFromYaw(0.0);
s1.request.initial_pose = p1;
s1.request.reference_frame = "";
if (spawn.call(s1))
{
ROS_INFO("success");
}
else
{
ROS_ERROR("Failed to call service");
return 1;
}
return 0; }
Does anyone know what is wrong with it?
Thanks
Asked by jasonwang538@gmail.com on 2017-04-21 23:57:15 UTC
Answers
Please reformat your code. Xacro is not processed automatically. You have to call xacro transformer by yourself to get the urdf first.
Asked by eugene-katsevman on 2017-04-22 09:37:51 UTC
Comments
I already get transformed .urdf file. But it has another problem. I use hector_quadrotor package from ros website. In the generated .urdf file, there is a plugin called libgazebo_ros_control plugin.This plugin needs to read params from parameter server, which is normally down in .launch file. But, all work should be done in c++ file. So, I am confused how to fully spawn a quadrotor model just through c++ file. Do you have some ideas towards this problem?
Asked by jasonwang538@gmail.com on 2017-04-22 09:43:01 UTC
what about putting needed params to param server through the param server service?
Asked by eugene-katsevman on 2017-04-22 10:22:06 UTC
http://wiki.ros.org/roscpp/Overview/Parameter%20Server
Asked by eugene-katsevman on 2017-04-22 10:22:50 UTC
It is a really good suggestion and I tried it. I use nh.setParam("/robot_desription", ?); to set the parameter value before I spawn the model so that the urdf can find relevant parameter in the server. But, I do not know what is the value for this ''/robot_description' parameter. I did not find much relevant information about it. Sir, do you have some ideas towards it?
Asked by jasonwang538@gmail.com on 2017-04-22 11:55:01 UTC
robot_description is usually the URDF as a string
Asked by eugene-katsevman on 2017-04-22 13:29:34 UTC
Excuse me, Sir. Do you means I need to read the content of robot urdf, then transfer that content to a string and assing the string to robot_description? Because I download the hector quadrotor package and the robot is described by a .xacro file. In .launch file, parameters are passed to the parameter server. In order to call spawn_urdf_model service, I must use a .urdf file.
Asked by jasonwang538@gmail.com on 2017-04-23 00:08:03 UTC
After this transformation from .xacro to .urdf, I can only use all things in original .xacro file and some parameters in .launch can not be passed. I need to use c++ to control this spawn so that parameters in .launch file are not passed to robot_description parameter. Therefore, every time I spawned a new model the gazebo is stuck and show up message like "gazebo_ros_control plugin is waiting for model URDF in parameter [robot_description] on the ROS param server". I feed so confused about it.
Asked by jasonwang538@gmail.com on 2017-04-23 00:11:31 UTC
I don't understand what you mean there. You're trying to pass xacro file to param server as robot_description. This is wrong. Transform it to URDF first. Then pass it to paramserver. You can do xacro transform from launch file ( ) or you can run in from your c++ code with system call.
Asked by eugene-katsevman on 2017-04-24 08:23:00 UTC
Sorry for my unclear explanation. More specifically, I need to spawn a hector quadrotor that really can be controlled instead of just a model. And this spawn must occur in C++ file as a external nodel for controlling the robot. So far, I only have .xacro file for descripting the quadortor model and .launch file which include .xacro file and other necessary control nodes. So I am wondering how to realize this. Do you have some ideas, sir?
Asked by jasonwang538@gmail.com on 2017-04-25 00:58:29 UTC
You're asking a different question here, but this is not a discussion board. If your original problem (loading xacro through service ) was resolved, please confirm it and ask another question as separate.
Asked by eugene-katsevman on 2017-04-25 08:36:26 UTC
Comments