Skip to content

Commit

Permalink
Add waitForService to fix service connections
Browse files Browse the repository at this point in the history
  • Loading branch information
jspricke committed May 13, 2014
1 parent b7fd990 commit 42600df
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 1 deletion.
6 changes: 5 additions & 1 deletion src/laserscanner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,12 +164,16 @@ bool scan(kurt3d::Scan::Request &req,

int main(int argc, char **argv)
{
ros::init(argc, argv, "laserscanner_server");
ros::init(argc, argv, "laserscanner_node");


ros::NodeHandle n;

client = n.serviceClient<kurt3d::ServoCommand>("servo_node");

ROS_INFO("Waiting for [assemble_scans2] to be advertised");
ros::service::waitForService("assemble_scans2");
ROS_INFO("Found assemble_scans2! Starting the laserscanner_node");
pointCloudClient = n.serviceClient<laser_assembler::AssembleScans2>("assemble_scans2");

// inits the publisher
Expand Down
3 changes: 3 additions & 0 deletions src/ps3joy_kurt3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,9 @@ int main(int argc, char** argv)
vel_pub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
ros::Subscriber ps3joy_sub = nh.subscribe("joy", 10, ps3joyCallback);

ROS_INFO("Waiting for [laserscanner_node] to be advertised");
ros::service::waitForService("assemble_scans2");
ROS_INFO("Found laserscanner_node! Starting the ps3joy_kurt3d");
client = nh.serviceClient<kurt3d::Scan>("laserscanner_node");

servo_pub = nh.advertise<sensor_msgs::JointState>("servo_control", 1);
Expand Down

0 comments on commit 42600df

Please sign in to comment.