|
From: <hsu...@us...> - 2008-09-23 00:39:36
|
Revision: 4566
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4566&view=rev
Author: hsujohnhsu
Date: 2008-09-23 00:39:27 +0000 (Tue, 23 Sep 2008)
Log Message:
-----------
update advertise and subscribe with default queue length of 10.
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/F3D.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/P3D.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Camera.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Laser.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Time.cc
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2008-09-22 23:10:31 UTC (rev 4565)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2008-09-23 00:39:27 UTC (rev 4566)
@@ -561,10 +561,10 @@
node->advertise_service(prefix + "/set_command", &BaseControllerNode::setCommand, this);
node->advertise_service(prefix + "/get_actual", &BaseControllerNode::getCommand, this); //FIXME: this is actually get command, just returning command for testing.
- node->advertise<std_msgs::RobotBase2DOdom>("odom");
+ node->advertise<std_msgs::RobotBase2DOdom>("odom",10);
// receive messages from 2dnav stack
- node->subscribe("cmd_vel", baseVelMsg, &BaseControllerNode::CmdBaseVelReceived, this);
+ node->subscribe("cmd_vel", baseVelMsg, &BaseControllerNode::CmdBaseVelReceived, this,10);
// for publishing odometry frame transforms odom
this->tfs = new rosTFServer(*node); //, true, 1 * 1000000000ULL, 0ULL);
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/F3D.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/F3D.cc 2008-09-22 23:10:31 UTC (rev 4565)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/F3D.cc 2008-09-23 00:39:27 UTC (rev 4566)
@@ -87,7 +87,7 @@
this->frameName = node->GetString("frameName", "", 1);
std::cout << "==== topic name for F3D ======== " << this->topicName << std::endl;
- rosnode->advertise<std_msgs::Vector3Stamped>(this->topicName);
+ rosnode->advertise<std_msgs::Vector3Stamped>(this->topicName,10);
}
////////////////////////////////////////////////////////////////////////////////
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/P3D.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/P3D.cc 2008-09-22 23:10:31 UTC (rev 4565)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/P3D.cc 2008-09-23 00:39:27 UTC (rev 4566)
@@ -89,7 +89,7 @@
this->rpyOffsets = node->GetVector3("rpyOffsets", Vector3(0,0,0));
std::cout << "==== topic name for P3D ======== " << this->topicName << std::endl;
- rosnode->advertise<std_msgs::TransformWithRateStamped>(this->topicName);
+ rosnode->advertise<std_msgs::TransformWithRateStamped>(this->topicName,10);
}
////////////////////////////////////////////////////////////////////////////////
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc 2008-09-22 23:10:31 UTC (rev 4565)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc 2008-09-23 00:39:27 UTC (rev 4566)
@@ -96,7 +96,7 @@
this->topicName = node->GetString("topicName","default_ros_laser",0); //read from xml file
std::cout << "================= " << this->topicName << std::endl;
- rosnode->advertise<std_msgs::PointCloudFloat32>(this->topicName);
+ rosnode->advertise<std_msgs::PointCloudFloat32>(this->topicName,10);
this->frameName = node->GetString("frameName","default_ros_laser",0); //read from xml file
this->gaussianNoise = node->GetDouble("gaussianNoise",0.0,0); //read from xml file
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Camera.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Camera.cc 2008-09-22 23:10:31 UTC (rev 4565)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Camera.cc 2008-09-23 00:39:27 UTC (rev 4566)
@@ -93,7 +93,7 @@
this->frameName = node->GetString("frameName","default_ros_camera",0); //read from xml file
std::cout << "================= " << this->topicName << std::endl;
- rosnode->advertise<std_msgs::Image>(this->topicName);
+ rosnode->advertise<std_msgs::Image>(this->topicName,10);
}
////////////////////////////////////////////////////////////////////////////////
@@ -135,13 +135,12 @@
// Finalize the controller
void Ros_Camera::FiniChild()
{
+ rosnode->unadvertise(this->topicName);
// TODO: will be replaced by global ros node eventually
if (rosnode != NULL)
{
std::cout << "shutdown rosnode in Ros_Camera" << std::endl;
- //ros::fini();
rosnode->shutdown();
- //delete rosnode;
}
}
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Laser.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Laser.cc 2008-09-22 23:10:31 UTC (rev 4565)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Laser.cc 2008-09-23 00:39:27 UTC (rev 4566)
@@ -96,7 +96,7 @@
this->topicName = node->GetString("topicName","default_ros_laser",0); //read from xml file
std::cout << "================= " << this->topicName << std::endl;
- rosnode->advertise<std_msgs::LaserScan>(this->topicName);
+ rosnode->advertise<std_msgs::LaserScan>(this->topicName,10);
this->frameName = node->GetString("frameName","default_ros_laser",0); //read from xml file
this->gaussianNoise = node->GetDouble("gaussianNoise",0.0,0); //read from xml file
}
@@ -151,13 +151,12 @@
// Finalize the controller
void Ros_Laser::FiniChild()
{
+ rosnode->unadvertise(this->topicName);
// TODO: will be replaced by global ros node eventually
if (rosnode != NULL)
{
std::cout << "shutdown rosnode in Ros_Laser" << std::endl;
- //ros::fini();
rosnode->shutdown();
- //delete rosnode;
}
}
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc 2008-09-22 23:10:31 UTC (rev 4565)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc 2008-09-23 00:39:27 UTC (rev 4566)
@@ -129,8 +129,8 @@
std::cout << " publishing state topic for ptz " << this->stateTopicName << std::endl;
std::cout << " subscribing command topic for ptz " << this->commandTopicName << std::endl;
- rosnode->advertise<axis_cam::PTZActuatorState>(this->stateTopicName);
- rosnode->subscribe( commandTopicName, PTZControlMessage, &Ros_PTZ::PTZCommandReceived,this);
+ rosnode->advertise<axis_cam::PTZActuatorState>(this->stateTopicName,10);
+ rosnode->subscribe( commandTopicName, PTZControlMessage, &Ros_PTZ::PTZCommandReceived,this,10);
if (!this->panJoint)
gzthrow("couldn't get pan hinge joint");
@@ -227,6 +227,12 @@
{
rosnode->unadvertise(this->stateTopicName);
rosnode->unsubscribe(commandTopicName);
+ // TODO: will be replaced by global ros node eventually
+ if (rosnode != NULL)
+ {
+ std::cout << "shutdown rosnode in Ros_PTZ" << std::endl;
+ rosnode->shutdown();
+ }
}
////////////////////////////////////////////////////////////////////////////////
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Time.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Time.cc 2008-09-22 23:10:31 UTC (rev 4565)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Time.cc 2008-09-23 00:39:27 UTC (rev 4566)
@@ -59,7 +59,7 @@
}
// for rostime
- rosnode_->advertise<rostools::Time>("time");
+ rosnode_->advertise<rostools::Time>("time",10);
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|