|
From: <hsu...@us...> - 2008-06-25 06:39:24
|
Revision: 963
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=963&view=rev
Author: hsujohnhsu
Date: 2008-06-24 23:39:30 -0700 (Tue, 24 Jun 2008)
Log Message:
-----------
removed pr2HW dependence from gazebo_plugin.
typo fix in setup.bash for rosgazebo.
call hw.Init() in pr2API.
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/libpr2API/src/pr2API.cpp
pkg/trunk/simulators/gazebo_plugin/Makefile
pkg/trunk/simulators/gazebo_plugin/include/gazebo_plugin/Pr2_Actarray.hh
pkg/trunk/simulators/gazebo_plugin/manifest.xml
pkg/trunk/simulators/rosgazebo/setup.bash
Modified: pkg/trunk/drivers/robot/pr2/libpr2API/src/pr2API.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2API/src/pr2API.cpp 2008-06-25 05:20:01 UTC (rev 962)
+++ pkg/trunk/drivers/robot/pr2/libpr2API/src/pr2API.cpp 2008-06-25 06:39:30 UTC (rev 963)
@@ -14,6 +14,8 @@
PR2_ERROR_CODE PR2Robot::InitializeRobot()
{
+ // initialize robot
+ hw.Init();
return PR2_ALL_OK;
}
Modified: pkg/trunk/simulators/gazebo_plugin/Makefile
===================================================================
--- pkg/trunk/simulators/gazebo_plugin/Makefile 2008-06-25 05:20:01 UTC (rev 962)
+++ pkg/trunk/simulators/gazebo_plugin/Makefile 2008-06-25 06:39:30 UTC (rev 963)
@@ -8,7 +8,6 @@
LDFLAGS = $(shell rospack export/cpp/lflags gazebo) \
$(shell rospack export/cpp/lflags pr2Core) \
$(shell rospack export/cpp/lflags controllers) \
- $(shell rospack export/cpp/lflags libpr2HW) \
$(shell rospack export/cpp/lflags newmat10)
LIB_ACT = lib/libPr2_Actarray.a
Modified: pkg/trunk/simulators/gazebo_plugin/include/gazebo_plugin/Pr2_Actarray.hh
===================================================================
--- pkg/trunk/simulators/gazebo_plugin/include/gazebo_plugin/Pr2_Actarray.hh 2008-06-25 05:20:01 UTC (rev 962)
+++ pkg/trunk/simulators/gazebo_plugin/include/gazebo_plugin/Pr2_Actarray.hh 2008-06-25 06:39:30 UTC (rev 963)
@@ -34,9 +34,6 @@
#include <vector>
#include <controllers/Pid.h>
-// actuator class, this should have identical calls for SIM and HW
-#include <libpr2HW/pr2HW.h>
-
namespace gazebo
{
class HingeJoint;
Modified: pkg/trunk/simulators/gazebo_plugin/manifest.xml
===================================================================
--- pkg/trunk/simulators/gazebo_plugin/manifest.xml 2008-06-25 05:20:01 UTC (rev 962)
+++ pkg/trunk/simulators/gazebo_plugin/manifest.xml 2008-06-25 06:39:30 UTC (rev 963)
@@ -12,7 +12,6 @@
<depend package="pr2Core"/>
<depend package="newmat10"/>
<depend package="controllers"/>
-<depend package="libpr2HW"/>
<export>
<cpp cflags="-I${prefix}/include" lflags="-L${prefix}/lib -lPr2_Actarray -lPr2_Gripper -lP3D"/>
</export>
Modified: pkg/trunk/simulators/rosgazebo/setup.bash
===================================================================
--- pkg/trunk/simulators/rosgazebo/setup.bash 2008-06-25 05:20:01 UTC (rev 962)
+++ pkg/trunk/simulators/rosgazebo/setup.bash 2008-06-25 06:39:30 UTC (rev 963)
@@ -2,7 +2,7 @@
export SIM_TOP=`rospack find gazebo`/gazebo-git
export SIM_PLUGIN=`rospack find gazebo_plugin`
export PR2API=`rospack find libpr2API`
-export PR2HW=`rospack find libprHW`
+export PR2HW=`rospack find libpr2HW`
export LD_LIBRARY_PATH=$PR2API/lib:$LD_LIBRARY_PATH
export LD_LIBRARY_PATH=$PR2HW/lib:$LD_LIBRARY_PATH
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-07-03 00:43:06
|
Revision: 1234
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=1234&view=rev
Author: hsujohnhsu
Date: 2008-07-02 17:43:14 -0700 (Wed, 02 Jul 2008)
Log Message:
-----------
fix indents for pr2.xml and base_node.cpp.
increase saturationTorques for spine elevator slider in sim.
Modified Paths:
--------------
pkg/trunk/demos/2dnav-gazebo/world/robot.world
pkg/trunk/demos/2dnav-gazebo/world/robot_test.world
pkg/trunk/demos/2dnav-gazebo/world/robot_torque.world
pkg/trunk/drivers/motor/etherdrive/src/base_node/base_node.cpp
pkg/trunk/drivers/robot/pr2/pr2Core/include/pr2Core/pr2.xml
Modified: pkg/trunk/demos/2dnav-gazebo/world/robot.world
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/world/robot.world 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/demos/2dnav-gazebo/world/robot.world 2008-07-03 00:43:14 UTC (rev 1234)
@@ -505,7 +505,7 @@
</joint>
<!-- ========================================= -->
<joint name="torso_spine_slider">
- <saturationTorque>100</saturationTorque>
+ <saturationTorque>1000</saturationTorque>
<pGain>1</pGain>
<dGain>0</dGain>
<iGain>0</iGain>
Modified: pkg/trunk/demos/2dnav-gazebo/world/robot_test.world
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/world/robot_test.world 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/demos/2dnav-gazebo/world/robot_test.world 2008-07-03 00:43:14 UTC (rev 1234)
@@ -505,7 +505,7 @@
</joint>
<!-- ========================================= -->
<joint name="torso_spine_slider">
- <saturationTorque>100</saturationTorque>
+ <saturationTorque>1000</saturationTorque>
<pGain>100</pGain>
<dGain>0</dGain>
<iGain>0</iGain>
Modified: pkg/trunk/demos/2dnav-gazebo/world/robot_torque.world
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/world/robot_torque.world 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/demos/2dnav-gazebo/world/robot_torque.world 2008-07-03 00:43:14 UTC (rev 1234)
@@ -505,8 +505,8 @@
</joint>
<!-- ========================================= -->
<joint name="torso_spine_slider">
- <saturationTorque>100</saturationTorque>
- <pGain>100</pGain>
+ <saturationTorque>1000</saturationTorque>
+ <pGain>1</pGain>
<dGain>0</dGain>
<iGain>0</iGain>
<iClamp>0</iClamp>
Modified: pkg/trunk/drivers/motor/etherdrive/src/base_node/base_node.cpp
===================================================================
--- pkg/trunk/drivers/motor/etherdrive/src/base_node/base_node.cpp 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/drivers/motor/etherdrive/src/base_node/base_node.cpp 2008-07-03 00:43:14 UTC (rev 1234)
@@ -35,215 +35,231 @@
class EtherDrive_Node : public ros::node
{
-public:
- std_msgs::ActuatorState mot[12];
- std_msgs::ActuatorCmd mot_cmd[12];
+ public:
+ std_msgs::ActuatorState mot[12];
+ std_msgs::ActuatorCmd mot_cmd[12];
- string host;
- string host2;
- EtherDrive *edRight;
- EtherDrive *edLeft;
- int frame_id;
+ string host;
+ string host2;
+ EtherDrive *edRight;
+ EtherDrive *edLeft;
+ int frame_id;
- float last_mot_val[12];
- double pulse_per_rad[12];
+ float last_mot_val[12];
+ double pulse_per_rad[12];
- int lastEncPos[12];
- int mode; // 0=voltage, 1=current, 2=position, 3=velocity, 4=position on comp
- bool firstTimeVelCtrl;
- int fooCounter;
- int counter;
- float last_mot_cmd[12];
+ int lastEncPos[12];
+ int mode; // 0=voltage, 1=current, 2=position, 3=velocity, 4=position on comp
+ bool firstTimeVelCtrl;
+ int fooCounter;
+ int counter;
+ float last_mot_cmd[12];
- EtherDrive_Node() : ros::node("etherdrive"), edLeft(NULL)
- {
- for (int i = 0;i < 12;i++) {
- ostringstream oss;
- oss << "mot" << i;
- advertise<std_msgs::ActuatorState>(oss.str().c_str());
+ EtherDrive_Node() : ros::node("etherdrive"), edLeft(NULL)
+ {
+ for (int i = 0;i < 12;i++)
+ {
+ ostringstream oss;
+ oss << "mot" << i;
+ advertise<std_msgs::ActuatorState>(oss.str().c_str());
- oss << "_cmd";
- subscribe(oss.str().c_str(), mot_cmd[i], &EtherDrive_Node::mot_callback);
- last_mot_val[i] = 0;
- }
+ oss << "_cmd";
+ subscribe(oss.str().c_str(), mot_cmd[i], &EtherDrive_Node::mot_callback);
+ last_mot_val[i] = 0;
+ }
- //if (!get_param(string(".host"), host))
- // host = "192.168.1.12";
-// host[0] = "10.12.0.103";
- host = "10.11.0.102";
- host2 = "10.12.0.103";
- printf("EtherDrive host set to [%s]\n",host.c_str());
+ //if (!get_param(string(".host"), host))
+ // host = "192.168.1.12";
+ // host[0] = "10.12.0.103";
+ host = "10.11.0.102";
+ host2 = "10.12.0.103";
+ printf("EtherDrive host set to [%s]\n",host.c_str());
- //if (!get_param(string(".frame_id"), frame_id))
- frame_id = -1;
- printf("EtherDrive frame_id set to [%d]\n", frame_id);
+ //if (!get_param(string(".frame_id"), frame_id))
+ frame_id = -1;
+ printf("EtherDrive frame_id set to [%d]\n", frame_id);
- for (int i = 0;i < 12;i++) {
- ostringstream oss;
- oss << "pulse_per_rad" << i;
- //if (!get_param(oss.str().c_str(), pulse_per_rad[i]))
- pulse_per_rad[i] = 1591.54943;
- printf("Using %g pulse_per_rad for motor %d\n", pulse_per_rad[i], i);
- }
+ for (int i = 0;i < 12;i++)
+ {
+ ostringstream oss;
+ oss << "pulse_per_rad" << i;
+ //if (!get_param(oss.str().c_str(), pulse_per_rad[i]))
+ pulse_per_rad[i] = 1591.54943;
+ printf("Using %g pulse_per_rad for motor %d\n", pulse_per_rad[i], i);
+ }
- edLeft = new EtherDrive();
- edLeft->init(host, "10.11.0.3");
- edRight = new EtherDrive();
- edRight->init(host2, "10.12.0.2");
+ edLeft = new EtherDrive();
+ edLeft->init(host, "10.11.0.3");
+ edRight = new EtherDrive();
+ edRight->init(host2, "10.12.0.2");
- // debugging JS: initialize values
- for (int i = 0; i < 12; i++) {
- mot_cmd[i].valid = true;
- mot_cmd[i].rel = 0;
- mot_cmd[i].cmd = 0;
- }
- // debugging JS: initialize values
- for (int i = 0; i < 6; i++) {
- // setting gains on controls on ethercard drive
- edLeft->set_gain(i,'P',0);
- edLeft->set_gain(i,'I',10);
- edLeft->set_gain(i,'D',0);
- edLeft->set_gain(i,'W',100);
- edLeft->set_gain(i,'M',1004);
- edLeft->set_gain(i,'Z',1);
- edRight->set_gain(i,'P',0);
- edRight->set_gain(i,'I',10);
- edRight->set_gain(i,'D',0);
- edRight->set_gain(i,'W',100);
- edRight->set_gain(i,'M',1004);
- edRight->set_gain(i,'Z',1);
- }
-
-
- edLeft->set_control_mode(1); // 0=voltage, 1=current control
- edRight->set_control_mode(1); // 0=voltage, 1=current control
+ // debugging JS: initialize values
+ for (int i = 0; i < 12; i++)
+ {
+ mot_cmd[i].valid = true;
+ mot_cmd[i].rel = 0;
+ mot_cmd[i].cmd = 0;
+ }
+ // debugging JS: initialize values
+ for (int i = 0; i < 6; i++)
+ {
+ // setting gains on controls on ethercard drive
+ edLeft->set_gain(i,'P',0);
+ edLeft->set_gain(i,'I',10);
+ edLeft->set_gain(i,'D',0);
+ edLeft->set_gain(i,'W',100);
+ edLeft->set_gain(i,'M',1004);
+ edLeft->set_gain(i,'Z',1);
+ edRight->set_gain(i,'P',0);
+ edRight->set_gain(i,'I',10);
+ edRight->set_gain(i,'D',0);
+ edRight->set_gain(i,'W',100);
+ edRight->set_gain(i,'M',1004);
+ edRight->set_gain(i,'Z',1);
+ }
+
+
+ edLeft->set_control_mode(1); // 0=voltage, 1=current control
+ edRight->set_control_mode(1); // 0=voltage, 1=current control
- firstTimeVelCtrl = true;
- fooCounter = 0;
- edLeft->motors_on();
- edRight->motors_on();
+ firstTimeVelCtrl = true;
+ fooCounter = 0;
+ edLeft->motors_on();
+ edRight->motors_on();
- counter = 0;
- }
+ counter = 0;
+ }
- void mot_callback() {
- //printf("received motor 3 command %f\n", mot_cmd[3].val);
- }
+ void mot_callback()
+ {
+ //printf("received motor 3 command %f\n", mot_cmd[3].val);
+ }
- virtual ~EtherDrive_Node()
- {
- if (edRight) {
- printf("deleting edRight\n");
- delete edRight;
- }
- if (edLeft) {
- printf("deleting edLeft\n");
- delete edLeft;
+ virtual ~EtherDrive_Node()
+ {
+ if (edRight)
+ {
+ printf("deleting edRight\n");
+ delete edRight;
+ }
+ if (edLeft)
+ {
+ printf("deleting edLeft\n");
+ delete edLeft;
+ }
+ int footmp[6] = {0,0,0,0,0,0};
+ edLeft->drive(6,footmp);
+ edRight->drive(6,footmp);
}
- int footmp[6] = {0,0,0,0,0,0};
- edLeft->drive(6,footmp);
- edRight->drive(6,footmp);
- }
- bool do_tick()
- {
+ bool do_tick()
+ {
- int tmp_mot_cmd[12];
- int tmp_mot_cmd_left[6];
- int tmp_mot_cmd_right[6];
- int currEncPos[12];
+ int tmp_mot_cmd[12];
+ int tmp_mot_cmd_left[6];
+ int tmp_mot_cmd_right[6];
+ int currEncPos[12];
- float curVel;
- float desVel;
- float desPos[12];
-// float k_p[12] = {5,5,-1,5,5,-1, 5,5,-1,5,5,-1};
- float k_p[12] = {5,5,-0.5,5,5,-0.5, 5,5,-0.5,5,5,-0.5};
-// float k_p[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
- float k_i[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
- float k_d[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
-// float k_i[12] = {0,0,-0.01,0,0,-0.01, 0,0,-0.01,0,0,0};
-// float k_d[12] = {0,0,-0.08,0,0,-0.08, 0,0,-0.08,0,0,-0.08};
- float k_cross[12] = {-1, -1, 0 , -1, -1, 0, -1, -1, 0 , -1, -1, 0};
- float foo;
+ float curVel;
+ float desVel;
+ float desPos[12];
+ // float k_p[12] = {5,5,-1,5,5,-1, 5,5,-1,5,5,-1};
+ float k_p[12] = {5,5,-0.5,5,5,-0.5, 5,5,-0.5,5,5,-0.5};
+ // float k_p[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
+ float k_i[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
+ float k_d[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
+ // float k_i[12] = {0,0,-0.01,0,0,-0.01, 0,0,-0.01,0,0,0};
+ // float k_d[12] = {0,0,-0.08,0,0,-0.08, 0,0,-0.08,0,0,-0.08};
+ float k_cross[12] = {-1, -1, 0 , -1, -1, 0, -1, -1, 0 , -1, -1, 0};
+ float foo;
- float posError[12];
- float intPosError[12];
- float lastPosError[12];
+ float posError[12];
+ float intPosError[12];
+ float lastPosError[12];
- for (int i = 0; i < 12; i++) {
- mot_cmd[i].lock();
- if(i == 2|i == 5|i == 8|i == 11) { // turret motors, position control
- desPos[i] = float(mot_cmd[i].cmd)/360*90000;
- if(i < 6) posError[i] = desPos[i] - float(edLeft->get_enc(i));
- else posError[i] = desPos[i] - float(edRight->get_enc(i-6));
-if(i==11) printf("posError: %f, despos: %f, enc: %i\n", posError[i], desPos[i], edRight->get_enc(i-6));
+ for (int i = 0; i < 12; i++)
+ {
+ mot_cmd[i].lock();
+ if(i == 2|i == 5|i == 8|i == 11)
+ { // turret motors, position control
+ desPos[i] = float(mot_cmd[i].cmd)/360*90000;
+ if(i < 6) posError[i] = desPos[i] - float(edLeft->get_enc(i));
+ else posError[i] = desPos[i] - float(edRight->get_enc(i-6));
+ if(i==11) printf("posError: %f, despos: %f, enc: %i\n", posError[i], desPos[i], edRight->get_enc(i-6));
- tmp_mot_cmd[i] = int(k_p[i]*posError[i]) + int(k_d[i]*(posError[i]-lastPosError[i])/0.001) + int(k_i[i]*intPosError[i]);
+ tmp_mot_cmd[i] = int(k_p[i]*posError[i]) + int(k_d[i]*(posError[i]-lastPosError[i])/0.001) + int(k_i[i]*intPosError[i]);
- lastPosError[i] = posError[i];
- intPosError[i] += posError[i];
- }
- else { // wheels, velocity control
+ lastPosError[i] = posError[i];
+ intPosError[i] += posError[i];
+ }
+ else
+ { // wheels, velocity control
+
+ if(i<6) currEncPos[i] = edLeft->get_enc(i);
+ else currEncPos[i] = edRight->get_enc(i-6);
+ curVel = float(currEncPos[i] - lastEncPos[i])/9000*0.48;
+ desVel = mot_cmd[i].cmd; // enc units/msec. should be (wheel rev/s)
+ if(i == 0| i ==1) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[2]);
+ else if(i == 3| i ==4) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[5]);
+ else if(i == 6| i ==7) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[8]);
+ else if(i == 9| i ==10) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[11]);
+ lastEncPos[i] = currEncPos[i];
+ }
+
+ mot_cmd[i].valid = false; // set to invalid so we don't re-use
+ mot_cmd[i].unlock();
+ if(tmp_mot_cmd[i] > 3000)
+ {
+ tmp_mot_cmd[i] = 3000;
+ // printf("Max +ve current motor %i\n", i);
+ }
+ if(tmp_mot_cmd[i] < -3000)
+ {
+ tmp_mot_cmd[i] = -3000;
+ // printf("Max -ve current motor %i \n", i);
+ }
- if(i<6) currEncPos[i] = edLeft->get_enc(i);
- else currEncPos[i] = edRight->get_enc(i-6);
- curVel = float(currEncPos[i] - lastEncPos[i])/9000*0.48;
- desVel = mot_cmd[i].cmd; // enc units/msec. should be (wheel rev/s)
- if(i == 0| i ==1) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[2]);
- else if(i == 3| i ==4) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[5]);
- else if(i == 6| i ==7) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[8]);
- else if(i == 9| i ==10) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[11]);
- lastEncPos[i] = currEncPos[i];
}
- mot_cmd[i].valid = false; // set to invalid so we don't re-use
- mot_cmd[i].unlock();
- if(tmp_mot_cmd[i] > 3000) {
- tmp_mot_cmd[i] = 3000;
- // printf("Max +ve current motor %i\n", i);
+ // edLeft->drive(6,tmp_mot_cmd);
+ for(int i = 0; i<6; i++)
+ {
+ tmp_mot_cmd_left[i] = tmp_mot_cmd[i];
+ tmp_mot_cmd_right[i] = tmp_mot_cmd[i+6];
+ }
+ edLeft->drive(6,tmp_mot_cmd_left);
+ edRight->drive(6,tmp_mot_cmd_right);
+ // int footmp[6] = {500,500,0,500,500,0};
+ // edRight->drive(6,footmp);
+ // edLeft->drive(6,footmp);
+
+ int valLeft[6];
+ int valRight[6];
+ if (!edLeft->tick(6,valLeft))
+ {
+ return false;
}
- if(tmp_mot_cmd[i] < -3000) {
- tmp_mot_cmd[i] = -3000;
- // printf("Max -ve current motor %i \n", i);
+ if (!edRight->tick(6,valRight))
+ {
+ return false;
}
-
- }
-// edLeft->drive(6,tmp_mot_cmd);
- for(int i = 0; i<6; i++) {
- tmp_mot_cmd_left[i] = tmp_mot_cmd[i];
- tmp_mot_cmd_right[i] = tmp_mot_cmd[i+6];
- }
- edLeft->drive(6,tmp_mot_cmd_left);
- edRight->drive(6,tmp_mot_cmd_right);
-// int footmp[6] = {500,500,0,500,500,0};
-// edRight->drive(6,footmp);
-// edLeft->drive(6,footmp);
+
+ for (int i = 0; i < 6; i++)
+ {
+ mot[i].pos_valid = true;
+ mot[i].pos = edLeft->get_enc(i);
+ mot[i+6].pos = edRight->get_enc(i);
+ ostringstream oss;
+ oss << "mot" << i;
+ publish(oss.str().c_str(), mot[i]);
+ }
+ return true;
+ } // end do_tick()
- int valLeft[6];
- int valRight[6];
- if (!edLeft->tick(6,valLeft)) {
- return false;
- }
- if (!edRight->tick(6,valRight)) {
- return false;
- }
-
-
- for (int i = 0; i < 6; i++) {
- mot[i].pos_valid = true;
- mot[i].pos = edLeft->get_enc(i);
- mot[i+6].pos = edRight->get_enc(i);
- ostringstream oss;
- oss << "mot" << i;
- publish(oss.str().c_str(), mot[i]);
- }
- return true;
- } // end do_tick()
-
};
int main(int argc, char **argv)
@@ -251,7 +267,8 @@
ros::init(argc, argv);
EtherDrive_Node a;
printf("start\n");
- while (a.ok()) {
+ while (a.ok())
+ {
usleep(1000);
if (!a.do_tick())
{
Modified: pkg/trunk/drivers/robot/pr2/pr2Core/include/pr2Core/pr2.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2Core/include/pr2Core/pr2.xml 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/drivers/robot/pr2/pr2Core/include/pr2Core/pr2.xml 2008-07-03 00:43:14 UTC (rev 1234)
@@ -6,475 +6,472 @@
<!-- Begin constant dimensions -->
- <constants>
+ <constants>
- <wheel_length>0.03</wheel_length>
- <wheel_radius>0.08</wheel_radius>
+ <wheel_length>0.03</wheel_length>
+ <wheel_radius>0.08</wheel_radius>
- <shoulder_pan_length>0.4</shoulder_pan_length>
- <shoulder_pan_radius>0.05</shoulder_pan_radius>
+ <shoulder_pan_length>0.4</shoulder_pan_length>
+ <shoulder_pan_radius>0.05</shoulder_pan_radius>
- <shoulder_pitch_length>0.01</shoulder_pitch_length>
- <shoulder_pitch_radius>0.01</shoulder_pitch_radius>
+ <shoulder_pitch_length>0.01</shoulder_pitch_length>
+ <shoulder_pitch_radius>0.01</shoulder_pitch_radius>
- <shoulder_roll_length>0.4</shoulder_roll_length>
- <shoulder_roll_radius>0.05</shoulder_roll_radius>
+ <shoulder_roll_length>0.4</shoulder_roll_length>
+ <shoulder_roll_radius>0.05</shoulder_roll_radius>
- <elbow_pitch_length>0.09085</elbow_pitch_length>
- <elbow_pitch_radius>0.05</elbow_pitch_radius>
+ <elbow_pitch_length>0.09085</elbow_pitch_length>
+ <elbow_pitch_radius>0.05</elbow_pitch_radius>
- <forearm_roll_length>0.2237</forearm_roll_length>
- <forearm_roll_radius>0.05</forearm_roll_radius>
+ <forearm_roll_length>0.2237</forearm_roll_length>
+ <forearm_roll_radius>0.05</forearm_roll_radius>
- <wrist_pitch_length>0.01</wrist_pitch_length>
- <wrist_pitch_radius>0.01</wrist_pitch_radius>
+ <wrist_pitch_length>0.01</wrist_pitch_length>
+ <wrist_pitch_radius>0.01</wrist_pitch_radius>
- <wrist_roll_length>0.01</wrist_roll_length>
- <wrist_roll_radius>0.01</wrist_roll_radius>
+ <wrist_roll_length>0.01</wrist_roll_length>
+ <wrist_roll_radius>0.01</wrist_roll_radius>
- <base_length>0.5</base_length>
- <base_width>0.5</base_width>
- <base_height>0.1</base_height>
+ <base_length>0.5</base_length>
+ <base_width>0.5</base_width>
+ <base_height>0.1</base_height>
- <torso_length>0.3</torso_length>
- <torso_width>0.05</torso_width>
- <torso_height>0.8</torso_height>
+ <torso_length>0.3</torso_length>
+ <torso_width>0.05</torso_width>
+ <torso_height>0.8</torso_height>
- <head_pan_length>0.1</head_pan_length>
- <head_pan_radius>0.5</head_pan_radius>
+ <head_pan_length>0.1</head_pan_length>
+ <head_pan_radius>0.5</head_pan_radius>
- <head_tilt_length>0.25</head_tilt_length>
- <head_tilt_width>0.1</head_tilt_width>
- <head_tilt_height>0.15</head_tilt_height>
+ <head_tilt_length>0.25</head_tilt_length>
+ <head_tilt_width>0.1</head_tilt_width>
+ <head_tilt_height>0.15</head_tilt_height>
- </constants>
+ </constants>
<!-- End constant dimensions -->
- <templates>
- <define template="pr2_caster_visual">
- <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder"><!-- geometry specified using a simple geometric object -->
- <size>0 0</size>
- </geometry>
- </define>
+ <templates>
+ <define template="pr2_caster_visual">
+ <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder"><!-- geometry specified using a simple geometric object -->
+ <size>0 0</size>
+ </geometry>
+ </define>
- <define template="pr2_caster_inertial">
- <mass> 3.473082 </mass>
- <com> 0.007342 0.00015 0.095236 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.012411765597 -0.000711733678 0.00050272983 0.015218160428 -0.000004273467 0.011763977943 </inertia>
- </define>
+ <define template="pr2_caster_inertial">
+ <mass> 3.473082 </mass>
+ <com> 0.007342 0.00015 0.095236 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.012411765597 -0.000711733678 0.00050272983 0.015218160428 -0.000004273467 0.011763977943 </inertia>
+ </define>
- <define template="pr2_caster_joint" type="revolute">
- <axis> 0 0 1 </axis> <!-- direction of the joint in the local coordinate frame -->
- <anchor>0 0 0</anchor> <!-- point on the joint relative to the local coordinate frame -->
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_caster_joint" type="revolute">
+ <axis> 0 0 1 </axis> <!-- direction of the joint in the local coordinate frame -->
+ <anchor>0 0 0</anchor> <!-- point on the joint relative to the local coordinate frame -->
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_wheel_visual">
- <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder"><!-- geometry specified using a simple geometric object -->
- <size>wheel_length wheel_radius</size>
- </geometry>
- </define>
+ <define template="pr2_wheel_visual">
+ <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder"><!-- geometry specified using a simple geometric object -->
+ <size>wheel_length wheel_radius</size>
+ </geometry>
+ </define>
- <define template="pr2_wheel_inertial">
- <mass> 0.44036 </mass>
- <com> 0.000008 0.000008 0.008475 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.012411765597 -0.000711733678 0.00050272983 0.015218160428 -0.000004273467 0.011763977943 </inertia>
- </define>
+ <define template="pr2_wheel_inertial">
+ <mass> 0.44036 </mass>
+ <com> 0.000008 0.000008 0.008475 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.012411765597 -0.000711733678 0.00050272983 0.015218160428 -0.000004273467 0.011763977943 </inertia>
+ </define>
- <define template="pr2_wheel_joint" type="revolute">
- <axis> 0 1 0 </axis> <!-- direction of the joint in the local coordinate frame -->
- <anchor>0 0 0</anchor> <!-- point on the joint relative to the local coordinate frame -->
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_wheel_joint" type="revolute">
+ <axis> 0 1 0 </axis> <!-- direction of the joint in the local coordinate frame -->
+ <anchor>0 0 0</anchor> <!-- point on the joint relative to the local coordinate frame -->
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_shoulder_pan_joint" type="revolute">
- <axis> 0 0 1 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <limit> -M_PI/2 M_PI/2 </limit>
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_shoulder_pan_joint" type="revolute">
+ <axis> 0 0 1 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit> -M_PI/2 M_PI/2 </limit>
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_shoulder_pan_inertial">
- <mass> 16.29553 </mass>
- <com> -0.005215 -0.030552 -0.175743 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia>0.793291393007 0.003412032973 0.0096614481 0.818419457224 -0.033999499551 0.13915007406 </inertia>
- </define>
+ <define template="pr2_shoulder_pan_inertial">
+ <mass> 16.29553 </mass>
+ <com> -0.005215 -0.030552 -0.175743 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia>0.793291393007 0.003412032973 0.0096614481 0.818419457224 -0.033999499551 0.13915007406 </inertia>
+ </define>
- <define template="pr2_shoulder_pan_visual">
- <xyz>0 0 -shoulder_pan_length/2 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0 0 0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size> shoulder_pan_length shoulder_pan_radius </size>
- </geometry>
- </define>
+ <define template="pr2_shoulder_pan_visual">
+ <xyz>0 0 -shoulder_pan_length/2 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0 0 0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size> shoulder_pan_length shoulder_pan_radius </size>
+ </geometry>
+ </define>
- <define template="pr2_shoulder_pitch_joint" type="revolute">
- <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <limit> -0.6109 1.3090 </limit>
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_shoulder_pitch_joint" type="revolute">
+ <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit> -0.6109 1.3090 </limit>
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_shoulder_pitch_inertial">
- <mass> 2.41223 </mass>
- <com> -0.035895 0.014422 -0.028263</com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.016640333585 0.002696462583 0.001337742275 0.017232603914 -0.003605106514 0.018723553425</inertia>
- </define>
+ <define template="pr2_shoulder_pitch_inertial">
+ <mass> 2.41223 </mass>
+ <com> -0.035895 0.014422 -0.028263</com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.016640333585 0.002696462583 0.001337742275 0.017232603914 -0.003605106514 0.018723553425</inertia>
+ </define>
- <define template="pr2_shoulder_pitch_visual">
- <xyz>shoulder_pitch_length/2 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>M_PI/2 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size> shoulder_pitch_length shoulder_pitch_radius </size>
- </geometry>
- </define>
+ <define template="pr2_shoulder_pitch_visual">
+ <xyz>shoulder_pitch_length/2 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>M_PI/2 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size> shoulder_pitch_length shoulder_pitch_radius </size>
+ </geometry>
+ </define>
- <define template="pr2_shoulder_roll_joint" type="revolute">
- <axis> 1 0 0 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the...
[truncated message content] |
|
From: <hsu...@us...> - 2008-07-08 18:27:43
|
Revision: 1346
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=1346&view=rev
Author: hsujohnhsu
Date: 2008-07-08 11:27:52 -0700 (Tue, 08 Jul 2008)
Log Message:
-----------
beginning attempt at re-organizing rt loops, control modules, api, hw interfaces, robot description.
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/libpr2HW/include/libpr2HW/pr2HW.h
pkg/trunk/drivers/robot/pr2/libpr2HW/src/pr2HW.cpp
Added Paths:
-----------
pkg/trunk/simulators/pr2SimRT/
pkg/trunk/simulators/pr2SimRT/CMakeLists.txt
pkg/trunk/simulators/pr2SimRT/Makefile
pkg/trunk/simulators/pr2SimRT/manifest.xml
pkg/trunk/simulators/pr2SimRT/pr2SimRT.cc
pkg/trunk/simulators/pr2SimRT/ringbuffer.h
Modified: pkg/trunk/drivers/robot/pr2/libpr2HW/include/libpr2HW/pr2HW.h
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2HW/include/libpr2HW/pr2HW.h 2008-07-08 18:22:22 UTC (rev 1345)
+++ pkg/trunk/drivers/robot/pr2/libpr2HW/include/libpr2HW/pr2HW.h 2008-07-08 18:27:52 UTC (rev 1346)
@@ -321,6 +321,11 @@
public: PR2_ERROR_CODE GetBasePositionGroundTruth(double* x, double* y, double *z, double *roll, double *pitch, double *yaw);
/*! \fn
+ \brief Wait for Gazebo to update
+ TODO: put this in UpdateHW()?
+ */
+ public: PR2_ERROR_CODE ClientWait();
+ /*! \fn
\brief Send out the commands to the actual robot
*/
public: PR2_ERROR_CODE UpdateHW();
Modified: pkg/trunk/drivers/robot/pr2/libpr2HW/src/pr2HW.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2HW/src/pr2HW.cpp 2008-07-08 18:22:22 UTC (rev 1345)
+++ pkg/trunk/drivers/robot/pr2/libpr2HW/src/pr2HW.cpp 2008-07-08 18:27:52 UTC (rev 1346)
@@ -31,21 +31,21 @@
// these are the "hardware" interfaces //
// //
////////////////////////////////////////////////////////////////////
-static gazebo::Client *client;
-static gazebo::SimulationIface *simIface;
-static gazebo::PR2ArrayIface *pr2Iface;
-static gazebo::PR2ArrayIface *pr2HeadIface;
-static gazebo::PR2GripperIface *pr2GripperLeftIface;
-static gazebo::PR2GripperIface *pr2GripperRightIface;
-static gazebo::LaserIface *pr2LaserIface;
-static gazebo::LaserIface *pr2BaseLaserIface;
-static gazebo::CameraIface *pr2CameraIface;
-static gazebo::CameraIface *pr2CameraGlobalIface;
-static gazebo::CameraIface *pr2CameraHeadLeftIface;
-static gazebo::CameraIface *pr2CameraHeadRightIface;
-static gazebo::PositionIface *pr2LeftWristIface;
-static gazebo::PositionIface *pr2RightWristIface;
-static gazebo::PositionIface *pr2BaseIface;
+gazebo::Client *client;
+gazebo::SimulationIface *simIface;
+gazebo::PR2ArrayIface *pr2Iface;
+gazebo::PR2ArrayIface *pr2HeadIface;
+gazebo::PR2GripperIface *pr2GripperLeftIface;
+gazebo::PR2GripperIface *pr2GripperRightIface;
+gazebo::LaserIface *pr2LaserIface;
+gazebo::LaserIface *pr2BaseLaserIface;
+gazebo::CameraIface *pr2CameraIface;
+gazebo::CameraIface *pr2CameraGlobalIface;
+gazebo::CameraIface *pr2CameraHeadLeftIface;
+gazebo::CameraIface *pr2CameraHeadRightIface;
+gazebo::PositionIface *pr2LeftWristIface;
+gazebo::PositionIface *pr2RightWristIface;
+gazebo::PositionIface *pr2BaseIface;
////////////////////////////////////////////////////////////////////
// //
@@ -812,8 +812,13 @@
}
};
+PR2_ERROR_CODE PR2HW::ClientWait()
+{
+ // block until simulator update.
+ client->Wait();
+ return PR2_ALL_OK;
+}
-
PR2_ERROR_CODE PR2HW::UpdateHW()
{
Added: pkg/trunk/simulators/pr2SimRT/CMakeLists.txt
===================================================================
--- pkg/trunk/simulators/pr2SimRT/CMakeLists.txt (rev 0)
+++ pkg/trunk/simulators/pr2SimRT/CMakeLists.txt 2008-07-08 18:27:52 UTC (rev 1346)
@@ -0,0 +1,4 @@
+cmake_minimum_required(VERSION 2.6)
+include(rosbuild)
+rospack(pr2SimRT)
+rospack_add_executable(pr2SimRT pr2SimRT.cc)
Added: pkg/trunk/simulators/pr2SimRT/Makefile
===================================================================
--- pkg/trunk/simulators/pr2SimRT/Makefile (rev 0)
+++ pkg/trunk/simulators/pr2SimRT/Makefile 2008-07-08 18:27:52 UTC (rev 1346)
@@ -0,0 +1,3 @@
+SRC = pr2SimRT.cc
+OUT = pr2SimRT
+include $(shell rospack find mk)/cmake.mk
Added: pkg/trunk/simulators/pr2SimRT/manifest.xml
===================================================================
--- pkg/trunk/simulators/pr2SimRT/manifest.xml (rev 0)
+++ pkg/trunk/simulators/pr2SimRT/manifest.xml 2008-07-08 18:27:52 UTC (rev 1346)
@@ -0,0 +1,13 @@
+<package>
+ <description>A ROS node that wraps up the Gazebo robot simulator.</description>
+ <author>John M. Hsu</author>
+ <license>TBD</license>
+ <depend package="roscpp" />
+ <depend package="gazebo" />
+ <depend package="gazebo_plugin" />
+ <depend package="libpr2API" />
+ <depend package="pr2Core" />
+ <depend package="std_msgs" />
+ <depend package="rosthread" />
+ <depend package="rosTF" />
+</package>
Added: pkg/trunk/simulators/pr2SimRT/pr2SimRT.cc
===================================================================
--- pkg/trunk/simulators/pr2SimRT/pr2SimRT.cc (rev 0)
+++ pkg/trunk/simulators/pr2SimRT/pr2SimRT.cc 2008-07-08 18:27:52 UTC (rev 1346)
@@ -0,0 +1,704 @@
+/*
+ * rosgazebo
+ * Copyright (c) 2008, Willow Garage, Inc.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <math.h>
+
+// gazebo
+#include <gazebo/gazebo.h>
+#include <gazebo/GazeboError.hh>
+#include <libpr2API/pr2API.h>
+#include "ringbuffer.h"
+
+// roscpp
+#include <ros/node.h>
+// roscpp - laser
+#include <std_msgs/LaserScan.h>
+// roscpp - laser image (point cloud)
+#include <std_msgs/PointCloudFloat32.h>
+#include <std_msgs/Point3DFloat32.h>
+#include <std_msgs/ChannelFloat32.h>
+// roscpp - used for shutter message right now
+#include <std_msgs/Empty.h>
+// roscpp - used for broadcasting time over ros
+#include <rostools/Time.h>
+// roscpp - base
+#include <std_msgs/RobotBase2DOdom.h>
+#include <std_msgs/BaseVel.h>
+// roscpp - arm
+#include <std_msgs/PR2Arm.h>
+// roscpp - camera
+#include <std_msgs/Image.h>
+
+// for frame transforms
+#include <rosTF/rosTF.h>
+
+#include <time.h>
+#include <signal.h>
+
+// Our node
+class GazeboNode : public ros::node
+{
+ private:
+ // Messages that we'll send or receive
+ std_msgs::BaseVel velMsg;
+ std_msgs::LaserScan laserMsg;
+ std_msgs::PointCloudFloat32 cloudMsg;
+ std_msgs::PointCloudFloat32 full_cloudMsg;
+ std_msgs::Empty shutterMsg; // marks end of a cloud message
+ std_msgs::RobotBase2DOdom odomMsg;
+ rostools::Time timeMsg;
+
+ // A mutex to lock access to fields that are used in message callbacks
+ ros::thread::mutex lock;
+
+ // for frame transforms, publish frame transforms
+ rosTFServer tf;
+
+ // time step calculation
+ double lastTime, simTime;
+
+ // smooth vx, vw commands
+ double vxSmooth, vwSmooth;
+
+ // used to generate Gaussian noise (for PCD)
+ double GaussianKernel(double mu,double sigma);
+
+
+ public:
+ // Constructor; stage itself needs argc/argv. fname is the .world file
+ // that stage should load.
+ GazeboNode(int argc, char** argv, const char* fname);
+ ~GazeboNode();
+
+ // advertise / subscribe models
+ int SubscribeModels();
+
+ // Do one update of the simulator. May pause if the next update time
+ // has not yet arrived.
+ void Update();
+
+ // Message callback for a std_msgs::BaseVel message, which set velocities.
+ void cmdvelReceived();
+
+ // Message callback for a std_msgs::PR2Arm message, which sets arm configuration.
+ void cmd_leftarmconfigReceived();
+ void cmd_rightarmconfigReceived();
+
+ // laser range data
+ float ranges[GZ_LASER_MAX_RANGES];
+ uint8_t intensities[GZ_LASER_MAX_RANGES];
+
+ // camera data
+ std_msgs::Image img;
+
+ // camera data
+ std_msgs::PR2Arm leftarm;
+ std_msgs::PR2Arm rightarm;
+
+
+ // The main simulator object
+ PR2::PR2Robot* myPR2;
+
+ // for the point cloud data
+ ringBuffer<std_msgs::Point3DFloat32> *cloud_pts;
+ ringBuffer<float> *cloud_ch1;
+
+ // keep count for full cloud
+ int max_cloud_pts;
+
+ // clean up on interrupt
+ static void finalize(int);
+};
+
+void
+GazeboNode::cmd_rightarmconfigReceived()
+{
+ this->lock.lock();
+ /*
+ printf("turret angle: %.3f\n", this->rightarm.turretAngle);
+ printf("shoulder pitch : %.3f\n", this->rightarm.shoulderLiftAngle);
+ printf("shoulder roll: %.3f\n", this->rightarm.upperarmRollAngle);
+ printf("elbow pitch: %.3f\n", this->rightarm.elbowAngle);
+ printf("elbow roll: %.3f\n", this->rightarm.forearmRollAngle);
+ printf("wrist pitch angle: %.3f\n", this->rightarm.wristPitchAngle);
+ printf("wrist roll: %.3f\n", this->rightarm.wristRollAngle);
+ printf("gripper gap: %.3f\n", this->rightarm.gripperGapCmd);
+
+ double jointPosition[] = {this->rightarm.turretAngle,
+ this->rightarm.shoulderLiftAngle,
+ this->rightarm.upperarmRollAngle,
+ this->rightarm.elbowAngle,
+ this->rightarm.forearmRollAngle,
+ this->rightarm.wristPitchAngle,
+ this->rightarm.wristRollAngle,
+ this->rightarm.gripperGapCmd};
+ double jointSpeed[] = {0,0,0,0,0,0,0,0};
+
+// this->myPR2->SetArmJointPosition(PR2::PR2_LEFT_ARM, jointPosition, jointSpeed);
+ */
+ //*
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_R_PAN , this->rightarm.turretAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_R_SHOULDER_PITCH, this->rightarm.shoulderLiftAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_R_SHOULDER_ROLL , this->rightarm.upperarmRollAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_R_ELBOW_PITCH , this->rightarm.elbowAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_R_ELBOW_ROLL , this->rightarm.forearmRollAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_R_WRIST_PITCH , this->rightarm.wristPitchAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_R_WRIST_ROLL , this->rightarm.wristRollAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_R_GRIPPER , this->rightarm.gripperGapCmd, 0);
+ this->myPR2->hw.CloseGripper(PR2::PR2_RIGHT_GRIPPER, this->rightarm.gripperGapCmd, this->rightarm.gripperForceCmd);
+ //*/
+ this->lock.unlock();
+}
+
+
+void
+GazeboNode::cmd_leftarmconfigReceived()
+{
+ this->lock.lock();
+ /*
+ double jointPosition[] = {this->leftarm.turretAngle,
+ this->leftarm.shoulderLiftAngle,
+ this->leftarm.upperarmRollAngle,
+ this->leftarm.elbowAngle,
+ this->leftarm.forearmRollAngle,
+ this->leftarm.wristPitchAngle,
+ this->leftarm.wristRollAngle,
+ this->leftarm.gripperGapCmd};
+ double jointSpeed[] = {0,0,0,0,0,0,0,0};
+ this->myPR2->SetArmJointPosition(PR2::PR2_LEFT_ARM, jointPosition, jointSpeed);
+ */
+
+ //*
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_L_PAN , this->leftarm.turretAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_L_SHOULDER_PITCH, this->leftarm.shoulderLiftAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_L_SHOULDER_ROLL , this->leftarm.upperarmRollAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_L_ELBOW_PITCH , this->leftarm.elbowAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_L_ELBOW_ROLL , this->leftarm.forearmRollAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_L_WRIST_PITCH , this->leftarm.wristPitchAngle, 0);
+ this->myPR2->hw.SetJointServoCmd(PR2::ARM_L_WRIST_ROLL , this->leftarm.wristRollAngle, 0);
+// this->myPR2->SetJointServoCmd(PR2::ARM_L_GRIPPER , this->leftarm.gripperGapCmd, 0);
+ this->myPR2->hw.CloseGripper(PR2::PR2_LEFT_GRIPPER, this->leftarm.gripperGapCmd, this->leftarm.gripperForceCmd);
+ //*/
+ this->lock.unlock();
+}
+
+void
+GazeboNode::cmdvelReceived()
+{
+ this->lock.lock();
+ double dt;
+ double w11, w21, w12, w22;
+
+ // smooth out the commands by time decay
+ // with w1,w2=1, this means equal weighting for new command every second
+ this->myPR2->GetTime(&(this->simTime));
+ dt = simTime - lastTime;
+
+ // smooth if dt is larger than zero
+ if (dt > 0.0)
+ {
+ w11 = 1.0;
+ w21 = 1.0;
+ w12 = 1.0;
+ w22 = 1.0;
+ this->vxSmooth = (w11 * this->vxSmooth + w21*dt *this->velMsg.vx)/( w11 + w21*dt);
+ this->vwSmooth = (w12 * this->vwSmooth + w22*dt *this->velMsg.vw)/( w12 + w22*dt);
+ }
+
+ // when running with the 2dnav stack, we need to refrain from moving when steering angles are off.
+ // when operating with the keyboard, we need instantaneous setting of both velocity and angular velocity.
+
+ // std::cout << "received cmd: vx " << this->velMsg.vx << " vw " << this->velMsg.vw
+ // << " vxsmoo " << this->vxSmooth << " vxsmoo " << this->vwSmooth
+ // << " | steer erros: " << this->myPR2->BaseSteeringAngleError() << " - " << M_PI/100.0
+ // << std::endl;
+
+ // 2dnav: if steering angle is wrong, don't move or move slowly
+ if (this->myPR2->BaseSteeringAngleError() > M_PI/100.0)
+ {
+ // set steering angle only
+ this->myPR2->SetBaseSteeringAngle (this->vxSmooth,0.0,this->vwSmooth);
+ }
+ else
+ {
+ // set base velocity
+ this->myPR2->SetBaseCartesianSpeedCmd(this->vxSmooth, 0.0, this->vwSmooth);
+ }
+
+ // TODO: this is a hack, need to rewrite
+ // if we are trying to stop, send the command through
+ if (this->velMsg.vx == 0.0)
+ {
+ // set base velocity
+ this->myPR2->SetBaseCartesianSpeedCmd(this->vxSmooth, 0.0, this->vwSmooth);
+ }
+
+ this->lastTime = this->simTime;
+
+ this->lock.unlock();
+}
+
+GazeboNode::GazeboNode(int argc, char** argv, const char* fname) :
+ ros::node("pr2SimRT"),tf(*this)
+{
+ // initialize random seed
+ srand(time(NULL));
+
+ // Initialize robot object
+ this->myPR2 = new PR2::PR2Robot();
+ // Initialize connections
+ this->myPR2->InitializeRobot();
+ // Set control mode for the base
+ this->myPR2->SetBaseControlMode(PR2::PR2_CARTESIAN_CONTROL);
+ // this->myPR2->SetJointControlMode(PR2::CASTER_FL_STEER, PR2::TORQUE_CONTROL);
+ // this->myPR2->SetJointControlMode(PR2::CASTER_FR_STEER, PR2::TORQUE_CONTROL);
+ // this->myPR2->SetJointControlMode(PR2::CASTER_RL_STEER, PR2::TORQUE_CONTROL);
+ // this->myPR2->SetJointControlMode(PR2::CASTER_RR_STEER, PR2::TORQUE_CONTROL);
+
+
+ // Initialize ring buffer for point cloud data
+ this->cloud_pts = new ringBuffer<std_msgs::Point3DFloat32>();
+ this->cloud_ch1 = new ringBuffer<float>();
+
+ // FIXME: move this to Subscribe Models
+ param("tilting_laser/max_cloud_pts",max_cloud_pts, 10000);
+ this->cloud_pts->allocate(this->max_cloud_pts);
+ this->cloud_ch1->allocate(this->max_cloud_pts);
+
+ // Set control mode for the arms
+ // FIXME: right now this just sets default to pd control
+ //this->myPR2->SetArmControlMode(PR2::PR2_RIGHT_ARM, PR2::PR2_JOINT_CONTROL);
+ //this->myPR2->SetArmControlMode(PR2::PR2_LEFT_ARM, PR2::PR2_JOINT_CONTROL);
+ //------------------------------------------------------------
+
+ this->myPR2->EnableGripperLeft();
+ this->myPR2->EnableGripperRight();
+
+ this->myPR2->GetTime(&(this->lastTime));
+ this->myPR2->GetTime(&(this->simTime));
+
+ // set torques for driving the robot wheels
+ // this->myPR2->hw.SetJointTorque(PR2::CASTER_FL_DRIVE_L, 1000.0 );
+ // this->myPR2->hw.SetJointTorque(PR2::CASTER_FR_DRIVE_L, 1000.0 );
+ // this->myPR2->hw.SetJointTorque(PR2::CASTER_RL_DRIVE_L, 1000.0 );
+ // this->myPR2->hw.SetJointTorque(PR2::CASTER_RR_DRIVE_L, 1000.0 );
+ // this->myPR2->hw.SetJointTorque(PR2::CASTER_FL_DRIVE_R, 1000.0 );
+ // this->myPR2->hw.SetJointTorque(PR2::CASTER_FR_DRIVE_R, 1000.0 );
+ // this->myPR2->hw.SetJointTorque(PR2::CASTER_RL_DRIVE_R, 1000.0 );
+ // this->myPR2->hw.SetJointTorque(PR2::CASTER_RR_DRIVE_R, 1000.0 );
+}
+
+void GazeboNode::finalize(int)
+{
+ fprintf(stderr,"Caught sig, clean-up and exit\n");
+ sleep(1);
+ exit(-1);
+}
+
+
+int
+GazeboNode::SubscribeModels()
+{
+ //advertise<std_msgs::LaserScan>("laser");
+ advertise<std_msgs::LaserScan>("scan");
+ advertise<std_msgs::RobotBase2DOdom>("odom");
+ advertise<std_msgs::Image>("image");
+ advertise<std_msgs::PointCloudFloat32>("cloud");
+ advertise<std_msgs::PointCloudFloat32>("full_cloud");
+ advertise<std_msgs::Empty>("shutter");
+ advertise<std_msgs::PR2Arm>("left_pr2arm_pos");
+ advertise<std_msgs::PR2Arm>("right_pr2arm_pos");
+ advertise<rostools::Time>("time");
+
+ subscribe("cmd_vel", velMsg, &GazeboNode::cmdvelReceived);
+ subscribe("cmd_leftarmconfig", leftarm, &GazeboNode::cmd_leftarmconfigReceived);
+ subscribe("cmd_rightarmconfig", rightarm, &GazeboNode::cmd_rightarmconfigReceived);
+
+
+ return(0);
+}
+
+GazeboNode::~GazeboNode()
+{
+}
+
+double
+GazeboNode::GaussianKernel(double mu,double sigma)
+{
+ // using Box-Muller transform to generate two independent standard normally disbributed normal variables
+ // see wikipedia
+ double U = (double)rand()/(double)RAND_MAX; // normalized uniform random variable
+ double V = (double)rand()/(double)RAND_MAX; // normalized uniform random variable
+ double X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V);
+ //double Y = sqrt(-2.0 * ::log(U)) * sin( 2.0*M_PI * V); // the other indep. normal variable
+ // we'll just use X
+ // scale to our mu and sigma
+ X = sigma * X + mu;
+ return X;
+}
+
+void
+GazeboNode::Update()
+{
+ this->lock.lock();
+
+ float angle_min;
+ float angle_max;
+ float angle_increment;
+ float range_max;
+ uint32_t ranges_size;
+ uint32_t ranges_alloc_size;
+ uint32_t intensities_size;
+ uint32_t intensities_alloc_size;
+ std_msgs::Point3DFloat32 tmp_cloud_pt;
+
+ /***************************************************************/
+ /* */
+ /* laser - pitching */
+ /* */
+ /***************************************************************/
+ if (this->myPR2->hw.GetLaserRanges(PR2::LASER_HEAD,
+ &angle_min, &angle_max, &angle_increment,
+ &range_max, &ranges_size , &ranges_alloc_size,
+ &intensities_size, &intensities_alloc_size,
+ this->ranges , this->intensities) == PR2::PR2_ALL_OK)
+ {
+ for(unsigned int i=0;i<ranges_size;i++)
+ {
+ // get laser pitch angle
+ double laser_yaw, laser_pitch, laser_pitch_rate;
+ this->myPR2->hw.GetJointServoActual(PR2::HEAD_LASER_PITCH , &laser_pitch, &laser_pitch_rate);
+ // get laser yaw angle
+ laser_yaw = angle_min + (double)i * angle_increment;
+ //std::cout << " pit " << laser_pitch << "yaw " << laser_yaw
+ // << " amin " << angle_min << " inc " << angle_increment << std::endl;
+ // populating cloud data by range
+ double tmp_range = this->ranges[i];
+ // transform from range to x,y,z
+ tmp_cloud_pt.x = tmp_range * cos(laser_yaw) * cos(laser_pitch);
+ tmp_cloud_pt.y = tmp_range * sin(laser_yaw) ; //* cos(laser_pitch);
+ tmp_cloud_pt.z = tmp_range * cos(laser_yaw) * sin(laser_pitch);
+
+ // add gaussian noise
+ const double sigma = 0.02; // 2 centimeter sigma
+ tmp_cloud_pt.x = tmp_cloud_pt.x + GaussianKernel(0,sigma);
+ tmp_cloud_pt.y = tmp_cloud_pt.y + GaussianKernel(0,sigma);
+ tmp_cloud_pt.z = tmp_cloud_pt.z + GaussianKernel(0,sigma);
+
+ // add mixed pixel noise
+ // if this point is some threshold away from last, add mixing model
+
+ // push pcd point into structure
+ this->cloud_pts->add((std_msgs::Point3DFloat32)tmp_cloud_pt);
+ this->cloud_ch1->add(this->intensities[i]);
+ }
+ /***************************************************************/
+ /* */
+ /* point cloud from laser image */
+ /* */
+ /***************************************************************/
+ //std::cout << " pcd num " << this->cloud_pts->length << std::endl;
+ int num_channels = 1;
+ this->cloudMsg.set_pts_size(this->cloud_pts->length);
+ this->cloudMsg.set_chan_size(num_channels);
+ this->cloudMsg.chan[0].name = "intensities";
+ this->cloudMsg.chan[0].set_vals_size(this->cloud_ch1->length);
+
+ this->full_cloudMsg.set_pts_size(this->cloud_pts->length);
+ this->full_cloudMsg.set_chan_size(num_channels);
+ this->full_cloudMsg.chan[0].name = "intensities";
+ this->full_cloudMsg.chan[0].set_vals_size(this->cloud_ch1->length);
+
+ for(int i=0;i< this->cloud_pts->length ;i++)
+ {
+ this->cloudMsg.pts[i].x = this->cloud_pts->buffer[i].x;
+ this->cloudMsg.pts[i].y = this->cloud_pts->buffer[i].y;
+ this->cloudMsg.pts[i].z = this->cloud_pts->buffer[i].z;
+ this->cloudMsg.chan[0].vals[i] = this->cloud_ch1->buffer[i];
+
+ this->full_cloudMsg.pts[i].x = this->cloud_pts->buffer[i].x;
+ this->full_cloudMsg.pts[i].y = this->cloud_pts->buffer[i].y;
+ this->full_cloudMsg.pts[i].z = this->cloud_pts->buffer[i].z;
+ this->full_cloudMsg.chan[0].vals[i] = this->cloud_ch1->buffer[i];
+ }
+ publish("cloud",this->cloudMsg);
+ publish("full_cloud",this->full_cloudMsg);
+ //publish("shutter",this->shutterMsg);
+ }
+
+
+ /***************************************************************/
+ /* */
+ /* publish time */
+ /* */
+ /***************************************************************/
+ this->myPR2->GetTime(&(this->simTime));
+ timeMsg.rostime.sec = (unsigned long)floor(this->simTime);
+ timeMsg.rostime.nsec = (unsigned long)floor( 1e9 * ( this->simTime - this->laserMsg.header.stamp.sec) );
+ publish("time",timeMsg);
+
+ /***************************************************************/
+ /* */
+ /* laser - base */
+ /* */
+ /***************************************************************/
+ if (this->myPR2->hw.GetLaserRanges(PR2::LASER_BASE,
+ &angle_min, &angle_max, &angle_increment,
+ &range_max, &ranges_size , &ranges_alloc_size,
+ &intensities_size, &intensities_alloc_size,
+ this->ranges , this->intensities) == PR2::PR2_ALL_OK)
+ {
+ // Get latest laser data
+ this->laserMsg.angle_min = angle_min;
+ this->laserMsg.angle_max = angle_max;
+ this->laserMsg.angle_increment = angle_increment;
+ this->laserMsg.range_max = range_max;
+ this->laserMsg.set_ranges_size(ranges_size);
+ this->laserMsg.set_intensities_size(intensities_size);
+ for(unsigned int i=0;i<ranges_size;i++)
+ {
+ double tmp_range = this->ranges[i];
+ this->laserMsg.ranges[i] =tmp_range;
+ this->laserMsg.intensities[i] = this->intensities[i];
+ }
+
+ this->laserMsg.header.frame_id = FRAMEID_LASER;
+ this->laserMsg.header.stamp.sec = (unsigned long)floor(this->simTime);
+ this->laserMsg.header.stamp.nsec = (unsigned long)floor( 1e9 * ( this->simTime - this->laserMsg.header.stamp.sec) );
+
+ //publish("laser",this->laserMsg); // for laser_view FIXME: can alias this at the commandline or launch script
+ publish("scan",this->laserMsg); // for rosstage
+ }
+
+
+
+ /***************************************************************/
+ /* */
+ /* odometry */
+ /* */
+ /***************************************************************/
+ // Get latest odometry data
+ // Get velocities
+ double vx,vy,vw;
+ this->myPR2->GetBaseCartesianSpeedActual(&vx,&vy,&vw);
+ // Translate into ROS message format and publish
+ this->odomMsg.vel.x = vx;
+ this->odomMsg.vel.y = vy;
+ this->odomMsg.vel.th = vw;
+
+ // Get position
+ double x,y,z,roll,pitch,th;
+ this->myPR2->GetBasePositionActual(&x,&y,&z,&roll,&pitch,&th);
+ this->odomMsg.pos.x = x;
+ this->odomMsg.pos.y = y;
+ this->odomMsg.pos.th = th;
+ // this->odomMsg.stall = this->positionmodel->Stall();
+
+ // TODO: get the frame ID from somewhere
+ this->odomMsg.header.frame_id = FRAMEID_ODOM;
+
+ this->odomMsg.header.stamp.sec = (unsigned long)floor(this->simTime);
+ this->odomMsg.header.stamp.nsec = (unsigned long)floor( 1e9 * ( this->simTime - this->odomMsg.header.stamp.sec) );
+
+ /***************************************************************/
+ /* */
+ /* frame transforms */
+ /* */
+ /***************************************************************/
+ tf.sendInverseEuler(FRAMEID_ODOM,
+ FRAMEID_ROBOT,
+ odomMsg.pos.x,
+ odomMsg.pos.y,
+ 0.0,
+ odomMsg.pos.th,
+ 0.0,
+ 0.0,
+ odomMsg.header.stamp.sec,
+ odomMsg.header.stamp.nsec);
+
+ // This publish call resets odomMsg.header.stamp.sec and
+ // odomMsg.header.stamp.nsec to zero. Thus, it must be called *after*
+ // those values are reused in the sendInverseEuler() call above.
+ publish("odom",this->odomMsg);
+
+ /***************************************************************/
+ /* */
+ /* camera */
+ /* */
+ /***************************************************************/
+ uint32_t width, height, depth;
+ std::string compression, colorspace;
+ uint32_t buf_size;
+ static unsigned char buf[GAZEBO_CAMERA_MAX_IMAGE_SIZE];
+
+ // get image
+ //this->myPR2->hw.GetCameraImage(PR2::CAMERA_GLOBAL,
+ this->myPR2->hw.GetCameraImage(PR2::CAMERA_HEAD_RIGHT,
+ &width , &height ,
+ &depth ,
+ &compression , &colorspace ,
+ &buf_size , buf );
+ this->img.width = width;
+ this->img.height = height;
+ this->img.compression = compression;
+ this->img.colorspace = colorspace;
+
+ if(buf_size >0)
+ {
+ this->img.set_data_size(buf_size);
+
+ this->img.data = buf;
+ //memcpy(this->img.data,buf,data_size);
+
+ publish("image",this->img);
+ }
+
+ /***************************************************************/
+ /* */
+ /* pitching Hokuyo joint */
+ /* */
+ /***************************************************************/
+ static double dAngle = -1;
+ double simPitchFreq,simPitchAngle,simPitchRate,simPitchTimeScale,simPitchAmp,simPitchOffset;
+ simPitchFreq = 1.0/10.0;
+ simPitchTimeScale = 2.0*M_PI*simPitchFreq;
+ simPitchAmp = M_PI / 8.0;
+ simPitchOffset = -M_PI / 8.0;
+ simPitchAngle = simPitchOffset + simPitchAmp * sin(this->simTime * simPitchTimeScale);
+ simPitchRate = simPitchAmp * simPitchTimeScale * cos(this->simTime * simPitchTimeScale); // TODO: check rate correctness
+ this->myPR2->GetTime(&this->simTime);
+ //std::cout << "sim time: " << this->simTime << std::endl;
+ //std::cout << "ang: " << simPitchAngle*180.0/M_PI << "rate: " << simPitchRate*180.0/M_PI << std::endl;
+ this->myPR2->hw.SetJointTorque(PR2::HEAD_LASER_PITCH , 1000.0);
+ this->myPR2->hw.SetJointGains(PR2::HEAD_LASER_PITCH, 10.0, 0.0, 0.0);
+ this->myPR2->hw.SetJointServoCmd(PR2::HEAD_LASER_PITCH , simPitchAngle, simPitchRate);
+
+ if (dAngle * simPitchRate < 0.0)
+ {
+ dAngle = -dAngle;
+ publish("shutter",this->shutterMsg);
+ }
+
+ // should send shutter when changing direction, or wait for Tully to implement ring buffer in viewer
+
+
+ /***************************************************************/
+ /* */
+ /* arm */
+ /* grip...
[truncated message content] |
|
From: <jl...@us...> - 2008-04-12 03:17:10
|
Revision: 101
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=101&view=rev
Author: jleibs
Date: 2008-04-11 20:17:15 -0700 (Fri, 11 Apr 2008)
Log Message:
-----------
Added axis_ptz node to axis_cam. Flows for this are in unstable_flows until we decide a good representation. Camera_calibration now uses axis_cam.
Modified Paths:
--------------
pkg/trunk/axis_cam/build.yaml
pkg/trunk/axis_cam/include/axis_cam/axis_cam.h
pkg/trunk/axis_cam/manifest.xml
pkg/trunk/axis_cam/src/libaxis_cam/axis_cam.cpp
pkg/trunk/camera_calibration/manifest.xml
pkg/trunk/camera_calibration/nodes/run_cal
pkg/trunk/camera_calibration/src/calibrator/calibrator.cpp
Added Paths:
-----------
pkg/trunk/axis_cam/src/axis_ptz/
pkg/trunk/axis_cam/src/axis_ptz/Makefile
pkg/trunk/axis_cam/src/axis_ptz/axis_ptz.cpp
pkg/trunk/unstable_flows/
pkg/trunk/unstable_flows/build.yaml
pkg/trunk/unstable_flows/flows/
pkg/trunk/unstable_flows/flows/Actuator.flow
pkg/trunk/unstable_flows/flows/LensActuator.flow
pkg/trunk/unstable_flows/flows/LensActuatorNoSub.flow
pkg/trunk/unstable_flows/flows/PTZActuator.flow
pkg/trunk/unstable_flows/flows/PTZActuatorNoSub.flow
pkg/trunk/unstable_flows/manifest.xml
pkg/trunk/unstable_flows/rosbuild
Modified: pkg/trunk/axis_cam/build.yaml
===================================================================
--- pkg/trunk/axis_cam/build.yaml 2008-04-11 18:29:37 UTC (rev 100)
+++ pkg/trunk/axis_cam/build.yaml 2008-04-12 03:17:15 UTC (rev 101)
@@ -2,6 +2,7 @@
make:
- src/libaxis_cam
- src/axis_cam
+ - src/axis_ptz
- src/axis_cam_polled
- test/test_get
- test/test_ptz
Modified: pkg/trunk/axis_cam/include/axis_cam/axis_cam.h
===================================================================
--- pkg/trunk/axis_cam/include/axis_cam/axis_cam.h 2008-04-11 18:29:37 UTC (rev 100)
+++ pkg/trunk/axis_cam/include/axis_cam/axis_cam.h 2008-04-12 03:17:15 UTC (rev 101)
@@ -48,8 +48,16 @@
int get_focus();
bool set_iris(int iris = 0, bool relative = false, bool blocking = true);
int get_iris();
+
+ bool send_params(string params);
+ bool query_params();
+
void print_params();
+ int last_iris, last_focus;
+ double last_pan, last_tilt, last_zoom;
+ bool last_autofocus_enabled, last_autoiris_enabled;
+
private:
string ip;
uint8_t *jpeg_buf;
@@ -64,11 +72,7 @@
}
static size_t jpeg_write(void *buf, size_t size, size_t nmemb, void *userp);
static size_t ptz_write(void *buf, size_t size, size_t nmemb, void *userp);
- bool send_params(string params);
- bool query_params();
- int last_iris, last_focus;
- double last_pan, last_tilt, last_zoom;
- bool last_autofocus_enabled, last_autoiris_enabled;
+
};
#endif
Modified: pkg/trunk/axis_cam/manifest.xml
===================================================================
--- pkg/trunk/axis_cam/manifest.xml 2008-04-11 18:29:37 UTC (rev 100)
+++ pkg/trunk/axis_cam/manifest.xml 2008-04-12 03:17:15 UTC (rev 101)
@@ -15,5 +15,6 @@
<depend package="image_viewer"/>
<depend package="thread_utils"/>
<depend package="string_utils"/>
+<depend package="unstable_flows"/>
</package>
Added: pkg/trunk/axis_cam/src/axis_ptz/Makefile
===================================================================
--- pkg/trunk/axis_cam/src/axis_ptz/Makefile (rev 0)
+++ pkg/trunk/axis_cam/src/axis_ptz/Makefile 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,4 @@
+SRC = axis_ptz.cpp
+OUT = ../../nodes/axis_ptz
+PKG = axis_cam
+include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/node.mk
Added: pkg/trunk/axis_cam/src/axis_ptz/axis_ptz.cpp
===================================================================
--- pkg/trunk/axis_cam/src/axis_ptz/axis_ptz.cpp (rev 0)
+++ pkg/trunk/axis_cam/src/axis_ptz/axis_ptz.cpp 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,223 @@
+///////////////////////////////////////////////////////////////////////////////
+// The axis_cam package provides a library that talks to Axis IP-based cameras
+// as well as ROS nodes which use these libraries
+//
+// Copyright (C) 2008, Morgan Quigley
+//
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+// * Redistributions of source code must retain the above copyright notice,
+// this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright
+// notice, this list of conditions and the following disclaimer in the
+// documentation and/or other materials provided with the distribution.
+// * Neither the name of Stanford University nor the names of its
+// contributors may be used to endorse or promote products derived from
+// this software without specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+
+#include "ros/ros_slave.h"
+#include "unstable_flows/FlowPTZActuatorNoSub.h"
+#include "axis_cam/axis_cam.h"
+
+class Axis_PTZ : public ROS_Slave
+{
+public:
+ FlowPTZActuatorNoSub *ptz;
+ FlowPTZActuatorNoSub *ptz_control;
+
+ string axis_host;
+ AxisCam *cam;
+ int frame_id;
+
+ float pan;
+ bool pan_rel;
+ bool pan_valid;
+
+ float tilt;
+ bool tilt_rel;
+ bool tilt_valid;
+
+ float zoom;
+ bool zoom_rel;
+ bool zoom_valid;
+
+ float focus;
+ bool focus_rel;
+ bool focus_valid;
+
+ float iris;
+ bool iris_rel;
+ bool iris_valid;
+
+ ROS_Mutex control_mutex;
+
+ Axis_PTZ() : ROS_Slave(), cam(NULL), frame_id(0)
+ {
+ register_source(ptz = new FlowPTZActuatorNoSub("ptz"));
+ register_sink(ptz_control = new FlowPTZActuatorNoSub("ptz_control"), ROS_CALLBACK(Axis_PTZ, ptz_callback));
+ register_with_master();
+ if (!get_string_param(".host", axis_host))
+ {
+ printf("host parameter not specified; defaulting to 192.168.0.90\n");
+ axis_host = "192.168.0.90";
+ }
+ printf("axis_cam host set to [%s]\n", axis_host.c_str());
+ get_int_param(".frame_id", &frame_id);
+ cam = new AxisCam(axis_host);
+ printf("package path is [%s]\n", get_my_package_path().c_str());
+ }
+
+ virtual ~Axis_PTZ()
+ {
+ if (cam)
+ delete cam;
+ }
+
+ bool get_and_send_ptz()
+ {
+ if (!cam->query_params()) {
+ return false;
+ }
+
+ ptz->frame_id = frame_id;
+
+ ptz->pan_val = cam->last_pan;
+ ptz->pan_rel = false;
+ ptz->pan_valid = true;
+
+ ptz->tilt_val = cam->last_tilt;
+ ptz->tilt_rel = false;
+ ptz->tilt_valid = true;
+
+ ptz->lens_zoom_val = cam->last_zoom;
+ ptz->lens_zoom_rel = false;
+ ptz->lens_zoom_valid = true;
+
+ ptz->lens_focus_val = cam->last_focus;
+ if (cam->last_autofocus_enabled)
+ ptz->lens_focus_val = -1;
+ ptz->lens_focus_rel = false;
+ ptz->lens_focus_valid = true;
+
+ ptz->lens_iris_val = cam->last_iris;
+ if (cam->last_autoiris_enabled == true)
+ ptz->lens_iris_val = -1;
+ ptz->lens_iris_rel = false;
+ ptz->lens_iris_valid = true;
+
+ ptz->publish();
+ return true;
+ }
+
+ void ptz_callback()
+ {
+ control_mutex.lock();
+
+ if (ptz_control->pan_valid) {
+ pan = ptz_control->pan_val;
+ pan_rel = ptz_control->pan_rel;
+ pan_valid = true;
+ }
+
+ if (ptz_control->tilt_valid) {
+ tilt = ptz_control->tilt_val;
+ tilt_rel = ptz_control->tilt_rel;
+ tilt_valid = true;
+ }
+
+ if (ptz_control->lens_zoom_valid) {
+ zoom = ptz_control->lens_zoom_val;
+ zoom_rel = ptz_control->lens_zoom_rel;
+ zoom_valid = true;
+ }
+
+ if (ptz_control->lens_focus_valid) {
+ focus = ptz_control->lens_focus_val;
+ focus_rel = ptz_control->lens_focus_rel;
+ focus_valid = true;
+ }
+
+ if (ptz_control->lens_focus_valid) {
+ focus = ptz_control->lens_focus_val;
+ focus_rel = ptz_control->lens_focus_rel;
+ focus_valid = true;
+ }
+
+ if (ptz_control->lens_iris_valid) {
+ iris = ptz_control->lens_iris_val;
+ iris_rel = ptz_control->lens_iris_rel;
+ iris_valid = true;
+ }
+
+ control_mutex.unlock();
+ }
+
+ bool do_ptz_control() {
+
+ control_mutex.lock();
+
+ ostringstream oss;
+
+ if (pan_valid)
+ oss << (pan_rel ? "r" : "") << string("pan=") << pan << string("&");
+ if (tilt_valid)
+ oss << (tilt_rel ? "r" : "") << string("tilt=") << tilt << string("&");
+ if (zoom_valid)
+ oss << (zoom_rel ? "r" : "") << string("zoom=") << zoom << string("&");
+ if (focus_valid) {
+ if (!focus_rel && focus <= 0)
+ oss << string("autofocus=on&");
+ else
+ oss << string("autofocus=off&") << (focus_rel ? "r" : "") << string("focus=") << focus << string("&");
+ }
+ if (iris_valid) {
+ if (!iris_rel && iris <= 0)
+ oss << string("autoiris=on&");
+ else
+ oss << string("autoiris=off&") << (iris_rel ? "r" : "") << string("iris=") << iris << string("&");
+ }
+
+ if (oss.str().size() > 0) {
+ if (!cam->send_params(oss.str()))
+ return false;
+ pan_valid = tilt_valid = zoom_valid = focus_valid = iris_valid = false;
+ }
+
+ control_mutex.unlock();
+
+ return true;
+ }
+
+
+};
+
+int main(int argc, char **argv)
+{
+ Axis_PTZ a;
+ while (a.happy()) {
+ if (!a.get_and_send_ptz())
+ {
+ a.log(ROS::ERROR,"Couldn't acquire ptz info.");
+ break;
+ }
+ if (!a.do_ptz_control())
+ {
+ a.log(ROS::ERROR,"Couldn't command ptz.");
+ break;
+ }
+ }
+ return 0;
+}
+
Modified: pkg/trunk/axis_cam/src/libaxis_cam/axis_cam.cpp
===================================================================
--- pkg/trunk/axis_cam/src/libaxis_cam/axis_cam.cpp 2008-04-11 18:29:37 UTC (rev 100)
+++ pkg/trunk/axis_cam/src/libaxis_cam/axis_cam.cpp 2008-04-12 03:17:15 UTC (rev 101)
@@ -266,16 +266,18 @@
else if (tokens[0] == string("iris"))
last_iris = atoi(tokens[1].c_str());
else if (tokens[0] == string("autofocus"))
- last_autofocus_enabled = (tokens[1] == string("on") ? true : false);
+ last_autofocus_enabled = (tokens[1].substr(0,2) == string("on") ? true : false);
else if (tokens[0] == string("autoiris"))
- last_autoiris_enabled = (tokens[1] == string("on") ? true : false);
-/*
+ last_autoiris_enabled = (tokens[1].substr(0,2) == string("on") ? true : false);
+
+ /*
printf("line has %d tokens:\n", tokens.size());
for (int i = 0; i < tokens.size(); i++)
- printf(" [%s] ", tokens[i].c_str());
+ printf(" '%s' ", tokens[i].substr(0,2).c_str());
printf("\n");
-*/
+ */
}
+
ptz_ss_mutex.unlock();
return true;
}
Modified: pkg/trunk/camera_calibration/manifest.xml
===================================================================
--- pkg/trunk/camera_calibration/manifest.xml 2008-04-11 18:29:37 UTC (rev 100)
+++ pkg/trunk/camera_calibration/manifest.xml 2008-04-12 03:17:15 UTC (rev 101)
@@ -5,8 +5,9 @@
<author>Jeremy Leibs (email: le...@wi...)</author>
<license>BSD</license>
<depend package='roscpp'/>
-<depend package='driver_axis213'/>
+<depend package='axis_cam'/>
<depend package='common_flows'/>
+<depend package='unstable_flows'/>
<depend package='yamlgraph'/>
<depend package='sdl'/>
<depend package='simple_sdl_gui'/>
Modified: pkg/trunk/camera_calibration/nodes/run_cal
===================================================================
--- pkg/trunk/camera_calibration/nodes/run_cal 2008-04-11 18:29:37 UTC (rev 100)
+++ pkg/trunk/camera_calibration/nodes/run_cal 2008-04-12 03:17:15 UTC (rev 101)
@@ -2,15 +2,15 @@
(puts "aaaaaaaa no ROS_ROOT"; exit) if !ENV['ROS_ROOT']
require "#{`#{ENV['ROS_ROOT']}/rospack latest yamlgraph`}/lib/yamlgraph/ygl.rb"
g = YAMLGraph.new
-g.node 'driver_axis213/axis213_cam', {'launch'=>'xterm', }
-g.node 'driver_axis213/axis213_ptz', {'launch'=>'xterm'}
-g.param 'axis213_cam.host', '10.0.0.150'
-g.param 'axis213_ptz.host', '10.0.0.150'
+g.node 'axis_cam/axis_cam', {'launch'=>'xterm', }
+g.node 'axis_cam/axis_ptz', {'launch'=>'xterm'}
+g.param 'axis_cam.host', '10.0.0.150'
+g.param 'axis_ptz.host', '10.0.0.150'
g.node 'camera_calibration/calibrator', {'launch'=>'xterm'}
g.node 'simple_sdl_gui/gui', {'launch'=>'xterm'}
-g.flow 'axis213_cam:image_all', 'calibrator:image_in'
-g.flow 'axis213_ptz:ptz_observe_all', 'calibrator:observe'
-g.flow 'calibrator:control', 'axis213_ptz:ptz_control'
+g.flow 'axis_cam:image', 'calibrator:image_in'
+g.flow 'axis_ptz:ptz', 'calibrator:observe'
+g.flow 'calibrator:control', 'axis_ptz:ptz_control'
g.flow 'calibrator:image_out', 'gui:image'
g.flow 'gui:key', 'calibrator:key'
YAMLGraphLauncher.new.launch g
Modified: pkg/trunk/camera_calibration/src/calibrator/calibrator.cpp
===================================================================
--- pkg/trunk/camera_calibration/src/calibrator/calibrator.cpp 2008-04-11 18:29:37 UTC (rev 100)
+++ pkg/trunk/camera_calibration/src/calibrator/calibrator.cpp 2008-04-12 03:17:15 UTC (rev 101)
@@ -47,7 +47,7 @@
#include "ros/ros_slave.h"
#include "common_flows/FlowImage.h"
#include "common_flows/ImageCodec.h"
-#include "driver_axis213/FlowPTZPosition.h"
+#include "unstable_flows/FlowPTZActuatorNoSub.h"
#include "simple_sdl_gui/FlowSDLKeyEvent.h"
void matToScreen(CvMat *mat, const char* matname) {
@@ -70,8 +70,8 @@
FlowImage *image_out;
ImageCodec<FlowImage> *codec_out;
- FlowPTZPosition *control;
- FlowPTZPosition *observe;
+ FlowPTZActuatorNoSub *control;
+ FlowPTZActuatorNoSub *observe;
FlowSDLKeyEvent *key;
CvMat *cvimage_in;
@@ -99,8 +99,8 @@
register_source(image_out = new FlowImage("image_out"));
codec_out = new ImageCodec<FlowImage>(image_out);
- register_sink(observe = new FlowPTZPosition("observe"), ROS_CALLBACK(Calibrator, ptz_received));
- register_source(control = new FlowPTZPosition("control"));
+ register_sink(observe = new FlowPTZActuatorNoSub("observe"), ROS_CALLBACK(Calibrator, ptz_received));
+ register_source(control = new FlowPTZActuatorNoSub("control"));
register_sink(key = new FlowSDLKeyEvent("key"), ROS_CALLBACK(Calibrator, key_received));
register_with_master();
@@ -143,11 +143,11 @@
virtual ~Calibrator() { }
void key_received() {
- control->pan = 0;
- control->tilt = 0;
- control->zoom = 0;
- control->focus = 0;
- control->relative = true;
+ control->pan_valid = false;
+ control->tilt_valid = false;
+ control->lens_zoom_valid = false;
+ control->lens_focus_valid = false;
+ control->lens_iris_valid = false;
// std::cout << "Got keypress: " << key->data << std::endl;
@@ -155,35 +155,57 @@
if (key->state == SDL_PRESSED) {
switch (key->sym) {
case SDLK_UP:
- control->tilt += 1;
+ control->tilt_val = 1;
+ control->tilt_rel = true;
+ control->tilt_valid = true;
break;
case SDLK_DOWN:
- control->tilt -= 1;
+ control->tilt_val = -1;
+ control->tilt_rel = true;
+ control->tilt_valid = true;
break;
case SDLK_LEFT:
- control->pan -= 1;
+ control->pan_val = -1;
+ control->pan_rel = true;
+ control->pan_valid = true;
break;
case SDLK_RIGHT:
- control->pan += 1;
+ control->pan_val = 1;
+ control->pan_rel = true;
+ control->pan_valid = true;
break;
case 61:
- control->zoom += 100;
+ control->lens_zoom_val = 100;
+ control->lens_zoom_rel = true;
+ control->lens_zoom_valid = true;
break;
case 45:
- control->zoom -= 100;
+ control->lens_zoom_val = -100;
+ control->lens_zoom_rel = true;
+ control->lens_zoom_valid = true;
break;
case SDLK_RIGHTBRACKET:
- control->focus += 100;
+ control->lens_focus_val = 100;
+ control->lens_focus_rel = true;
+ control->lens_focus_valid = true;
break;
case SDLK_LEFTBRACKET:
- control->focus -= 100;
+ control->lens_focus_val = -100;
+ control->lens_focus_rel = true;
+ control->lens_focus_valid = true;
break;
case SDLK_SPACE:
- control->pan = 0;
- control->tilt = 0;
- control->zoom = 5000;
- control->focus = -1;
- control->relative = false;
+ control->pan_val = 0;
+ control->pan_rel = false;
+ control->pan_valid = true;
+
+ control->tilt_val = 0;
+ control->tilt_rel = false;
+ control->tilt_valid = true;
+
+ control->lens_zoom_val = 5000;
+ control->lens_zoom_rel = false;
+ control->lens_zoom_valid = true;
break;
case SDLK_c:
centering = !centering;
@@ -193,17 +215,17 @@
break;
case SDLK_f:
observe->lock_atom();
- control->pan = observe->pan;
- control->tilt = observe->tilt;
- control->zoom = observe->zoom;
- tmp_focus = observe->focus;
+ tmp_focus = observe->lens_focus_val;
observe->unlock_atom();
- control->relative = false;
- if (tmp_focus > 1) {
- control->focus = -1;
+ if (tmp_focus > 0) {
+ control->lens_focus_val = -1;
+ control->lens_focus_rel = false;
+ control->lens_focus_valid = true;
} else {
- control->focus = 0;
+ control->lens_focus_val = 0;
+ control->lens_focus_rel = true;
+ control->lens_focus_valid = true;
}
break;
case SDLK_RETURN:
@@ -279,10 +301,10 @@
std::ofstream posfile(ss.str().c_str());
observe->lock_atom();
- posfile << "P: " << observe->pan << std::endl
- << "T: " << observe->tilt << std::endl
- << "Z: " << observe->zoom << std::endl
- << "F: " << observe->focus;
+ posfile << "P: " << observe->pan_val << std::endl
+ << "T: " << observe->tilt_val << std::endl
+ << "Z: " << observe->lens_zoom_val << std::endl
+ << "F: " << observe->lens_focus_val;
observe->unlock_atom();
posfile.close();
@@ -303,10 +325,10 @@
std::stringstream ss;
observe->lock_atom();
- ss << "P: " << observe->pan;
- ss << " T: " << observe->tilt;
- ss << " Z: " << observe->zoom;
- ss << " F: " << observe->focus;
+ ss << "P: " << observe->pan_val;
+ ss << " T: " << observe->tilt_val;
+ ss << " Z: " << observe->lens_zoom_val;
+ ss << " F: " << observe->lens_focus_val;
observe->unlock_atom();
cvPutText(cvimage_undistort, ss.str().c_str(), cvPoint(15,30), &font, CV_RGB(255,0,0));
@@ -347,11 +369,14 @@
rel_pan = (COM.x - 354.0) * .001;
rel_tilt = -(COM.y - 240.0) * .001;
- control->pan = rel_pan;
- control->tilt = rel_tilt;
- control->zoom = 0;
- control->focus = 0;
- control->relative = true;
+ control->pan_val = rel_pan;
+ control->pan_rel = true;
+ control->pan_valid = true;
+
+ control->tilt_val = rel_tilt;
+ control->tilt_rel = true;
+ control->tilt_valid = true;
+
control->publish();
}
Added: pkg/trunk/unstable_flows/build.yaml
===================================================================
Added: pkg/trunk/unstable_flows/flows/Actuator.flow
===================================================================
--- pkg/trunk/unstable_flows/flows/Actuator.flow (rev 0)
+++ pkg/trunk/unstable_flows/flows/Actuator.flow 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,3 @@
+float32 val
+byte rel
+byte valid
Added: pkg/trunk/unstable_flows/flows/LensActuator.flow
===================================================================
--- pkg/trunk/unstable_flows/flows/LensActuator.flow (rev 0)
+++ pkg/trunk/unstable_flows/flows/LensActuator.flow 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,3 @@
+Actuator zoom
+Actuator focus
+Actuator iris
\ No newline at end of file
Added: pkg/trunk/unstable_flows/flows/LensActuatorNoSub.flow
===================================================================
--- pkg/trunk/unstable_flows/flows/LensActuatorNoSub.flow (rev 0)
+++ pkg/trunk/unstable_flows/flows/LensActuatorNoSub.flow 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,9 @@
+float32 zoom_val
+byte zoom_rel
+byte zoom_valid
+float32 focus_val
+byte focus_rel
+byte focus_valid
+float32 iris_val
+byte iris_rel
+byte iris_valid
Added: pkg/trunk/unstable_flows/flows/PTZActuator.flow
===================================================================
--- pkg/trunk/unstable_flows/flows/PTZActuator.flow (rev 0)
+++ pkg/trunk/unstable_flows/flows/PTZActuator.flow 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,4 @@
+Actuator pan
+Actuator tilt
+LensActuator lens
+
Added: pkg/trunk/unstable_flows/flows/PTZActuatorNoSub.flow
===================================================================
--- pkg/trunk/unstable_flows/flows/PTZActuatorNoSub.flow (rev 0)
+++ pkg/trunk/unstable_flows/flows/PTZActuatorNoSub.flow 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,17 @@
+float32 pan_val
+byte pan_rel
+byte pan_valid
+float32 tilt_val
+byte tilt_rel
+byte tilt_valid
+float32 lens_zoom_val
+byte lens_zoom_rel
+byte lens_zoom_valid
+float32 lens_focus_val
+byte lens_focus_rel
+byte lens_focus_valid
+float32 lens_iris_val
+byte lens_iris_rel
+byte lens_iris_valid
+
+
Added: pkg/trunk/unstable_flows/manifest.xml
===================================================================
--- pkg/trunk/unstable_flows/manifest.xml (rev 0)
+++ pkg/trunk/unstable_flows/manifest.xml 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,12 @@
+<package>
+ <description brief="Flows that have not yet been elevated to the status common_flows">
+This is a place to put flows that are more general than the module that needs to use them, but
+havn't been tested thoroughly enough to put in common_flows. Depending on these flows is
+likely to break things since they are subject to refactoring and/or moving at any time.
+ </description>
+ <author>Jeremy Leibs (email: le...@wi...)</author>
+ <license>BSD</license>
+ <url>http://pr.willowgarage.com</url>
+ <depend package="common_flows"/>
+</package>
+
Added: pkg/trunk/unstable_flows/rosbuild
===================================================================
--- pkg/trunk/unstable_flows/rosbuild (rev 0)
+++ pkg/trunk/unstable_flows/rosbuild 2008-04-12 03:17:15 UTC (rev 101)
@@ -0,0 +1,2 @@
+#!/usr/bin/env ruby
+exec("#{`#{ENV['ROS_ROOT']}/rospack find rostools`}/scripts/yamlbuild", 'build.yaml', *ARGV)
Property changes on: pkg/trunk/unstable_flows/rosbuild
___________________________________________________________________
Name: svn:executable
+ *
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2008-04-16 01:35:16
|
Revision: 104
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=104&view=rev
Author: jleibs
Date: 2008-04-15 18:35:21 -0700 (Tue, 15 Apr 2008)
Log Message:
-----------
Check in library for reading from elphel camera.
Added Paths:
-----------
pkg/trunk/elphel_cam/
pkg/trunk/elphel_cam/build.yaml
pkg/trunk/elphel_cam/include/
pkg/trunk/elphel_cam/include/elphel_cam/
pkg/trunk/elphel_cam/include/elphel_cam/elphel_cam.h
pkg/trunk/elphel_cam/lib/
pkg/trunk/elphel_cam/manifest.xml
pkg/trunk/elphel_cam/nodes/
pkg/trunk/elphel_cam/rosbuild
pkg/trunk/elphel_cam/src/
pkg/trunk/elphel_cam/src/libelphel_cam/
pkg/trunk/elphel_cam/src/libelphel_cam/Makefile
pkg/trunk/elphel_cam/src/libelphel_cam/elphel_cam.cpp
pkg/trunk/elphel_cam/test/
pkg/trunk/elphel_cam/test/test_cam/
pkg/trunk/elphel_cam/test/test_cam/Makefile
pkg/trunk/elphel_cam/test/test_cam/test_cam.cpp
Added: pkg/trunk/elphel_cam/build.yaml
===================================================================
--- pkg/trunk/elphel_cam/build.yaml (rev 0)
+++ pkg/trunk/elphel_cam/build.yaml 2008-04-16 01:35:21 UTC (rev 104)
@@ -0,0 +1,4 @@
+cpp:
+ make:
+ - src/libelphel_cam
+ - test/test_cam
Added: pkg/trunk/elphel_cam/include/elphel_cam/elphel_cam.h
===================================================================
--- pkg/trunk/elphel_cam/include/elphel_cam/elphel_cam.h (rev 0)
+++ pkg/trunk/elphel_cam/include/elphel_cam/elphel_cam.h 2008-04-16 01:35:21 UTC (rev 104)
@@ -0,0 +1,78 @@
+///////////////////////////////////////////////////////////////////////////////
+// The axis_cam package provides a library that talks to Axis IP-based cameras
+// as well as ROS nodes which use these libraries
+//
+// Copyright (C) 2008, Morgan Quigley, Stanford Univerity
+// Jeremy Leibs, Willow Garage
+//
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+// * Redistributions of source code must retain the above copyright notice,
+// this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright
+// notice, this list of conditions and the following disclaimer in the
+// documentation and/or other materials provided with the distribution.
+// * Neither the name of Stanford University, Willow Garage, nor the names
+// of its contributors may be used to endorse or promote products derived
+// from this software without specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+
+#ifndef ELPHEL_CAM_ELPHEL_CAM_H
+#define ELPHEL_CAM_ELPHEL_CAM_H
+
+#include <curl/curl.h>
+#include <string>
+#include <sstream>
+#include "thread_utils/mutex.h"
+
+using namespace std;
+
+class Elphel_Cam
+{
+public:
+ Elphel_Cam(string ip);
+ ~Elphel_Cam();
+
+ bool next_jpeg(uint8_t ** const fetch_jpeg_buf, uint32_t *fetch_buf_size);
+
+ bool config_cmd(string url, string cmd);
+
+ bool compressor_cmd(string cmd);
+ bool ccam_cmd(string cmd);
+ bool towp();
+
+ bool start();
+ bool stop();
+
+ bool init(float = 10, int = 4, int = 4);
+
+private:
+ string ip;
+ uint8_t *jpeg_buf, ;
+ uint32_t jpeg_buf_size, jpeg_file_size;
+
+ CURL *jpeg_curl, *config_curl;
+
+ char *image_url, *towp_url, *ccam_url, *comp_url;
+
+ stringstream config_ss;
+ ThreadUtils::Mutex config_ss_mutex;
+
+ static size_t jpeg_write(void *buf, size_t size, size_t nmemb, void *userp);
+ static size_t config_write(void *buf, size_t size, size_t nmemb, void *userp);
+
+};
+
+#endif
+
Added: pkg/trunk/elphel_cam/manifest.xml
===================================================================
--- pkg/trunk/elphel_cam/manifest.xml (rev 0)
+++ pkg/trunk/elphel_cam/manifest.xml 2008-04-16 01:35:21 UTC (rev 104)
@@ -0,0 +1,13 @@
+<package>
+<description brief="Controlling and acquiring data from the Elphel IP-based cameras">
+A package to configure and grab images from the Elphel IP-based camera.
+
+</description>
+<author>Jeremy Leibs (email: le...@wi...)</author>
+<license>BSD</license>
+<url>http://pr.willowgarage.com</url>
+<depend package="common_flows"/>
+<depend package="thread_utils"/>
+<depend package="image_viewer"/>
+</package>
+
Added: pkg/trunk/elphel_cam/rosbuild
===================================================================
--- pkg/trunk/elphel_cam/rosbuild (rev 0)
+++ pkg/trunk/elphel_cam/rosbuild 2008-04-16 01:35:21 UTC (rev 104)
@@ -0,0 +1,2 @@
+#!/usr/bin/env ruby
+exec("#{`#{ENV['ROS_ROOT']}/rospack find rostools`}/scripts/yamlbuild", 'build.yaml', *ARGV)
Property changes on: pkg/trunk/elphel_cam/rosbuild
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/elphel_cam/src/libelphel_cam/Makefile
===================================================================
--- pkg/trunk/elphel_cam/src/libelphel_cam/Makefile (rev 0)
+++ pkg/trunk/elphel_cam/src/libelphel_cam/Makefile 2008-04-16 01:35:21 UTC (rev 104)
@@ -0,0 +1,4 @@
+SRC = elphel_cam.cpp
+OUT = ../../lib/libelphel_cam.a
+PKG = elphel_cam
+include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/lib.mk
Added: pkg/trunk/elphel_cam/src/libelphel_cam/elphel_cam.cpp
===================================================================
--- pkg/trunk/elphel_cam/src/libelphel_cam/elphel_cam.cpp (rev 0)
+++ pkg/trunk/elphel_cam/src/libelphel_cam/elphel_cam.cpp 2008-04-16 01:35:21 UTC (rev 104)
@@ -0,0 +1,247 @@
+///////////////////////////////////////////////////////////////////////////////
+// The axis_cam package provides a library that talks to Axis IP-based cameras
+// as well as ROS nodes which use these libraries
+//
+// Copyright (C) 2008, Morgan Quigley, Stanford Univerity
+// Jeremy Leibs, Willow Garage
+//
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+// * Redistributions of source code must retain the above copyright notice,
+// this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright
+// notice, this list of conditions and the following disclaimer in the
+// documentation and/or other materials provided with the distribution.
+// * Neither the name of Stanford University, Willow Garage, nor the names
+// of its contributors may be used to endorse or promote products derived
+// from this software without specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+
+#include <sstream>
+#include <iostream>
+#include "elphel_cam/elphel_cam.h"
+
+Elphel_Cam::Elphel_Cam(string ip) : ip(ip)
+{
+ jpeg_buf = NULL;
+ jpeg_buf_size = 0;
+ curl_global_init(0);
+
+ ostringstream oss;
+ oss << "http://" << ip << ":8081/torp/wait/img/next/save";
+ image_url = new char[oss.str().length()+1];
+ strcpy(image_url, oss.str().c_str());
+
+
+ oss.str("");
+ oss << "http://" << ip << ":8081/towp/save";
+ towp_url = new char[oss.str().length()+1];
+ strcpy(towp_url, oss.str().c_str());
+
+ oss.str("");
+ oss << "http://" << ip << "/admin-bin/ccam.cgi?";
+ ccam_url = new char[oss.str().length()+1];
+ strcpy(ccam_url, oss.str().c_str());
+
+ oss.str("");
+ oss << "http://" << ip << ":81/compressor.php?";
+ comp_url = new char[oss.str().length()+1];
+ strcpy(comp_url, oss.str().c_str());
+
+ jpeg_curl = curl_easy_init();
+ curl_easy_setopt(jpeg_curl, CURLOPT_URL, image_url);
+ curl_easy_setopt(jpeg_curl, CURLOPT_WRITEFUNCTION, Elphel_Cam::jpeg_write);
+ curl_easy_setopt(jpeg_curl, CURLOPT_WRITEDATA, this);
+
+ config_curl = curl_easy_init();
+ // curl_easy_setopt(config_curl, CURLOPT_URL, config_url);
+ curl_easy_setopt(config_curl, CURLOPT_WRITEFUNCTION, Elphel_Cam::config_write);
+ curl_easy_setopt(config_curl, CURLOPT_WRITEDATA, this);
+
+
+}
+
+Elphel_Cam::~Elphel_Cam()
+{
+ delete[] image_url;
+ delete[] towp_url;
+ delete[] ccam_url;
+ delete[] comp_url;
+ if (jpeg_buf)
+ delete[] jpeg_buf;
+ jpeg_buf = NULL;
+ curl_global_cleanup();
+}
+
+bool Elphel_Cam::next_jpeg(uint8_t ** const fetch_jpeg_buf, uint32_t *fetch_buf_size)
+{
+ if (fetch_jpeg_buf && fetch_buf_size)
+ {
+ *fetch_jpeg_buf = NULL;
+ *fetch_buf_size = 0;
+ }
+ else
+ {
+ printf("woah! bad input parameters\n");
+ return false; // don't make me crash
+ }
+ CURLcode code;
+ do
+ {
+ jpeg_file_size = 0;
+ if (code = curl_easy_perform(jpeg_curl))
+ {
+ printf("woah! curl error: [%s]\n", curl_easy_strerror(code));
+ return false;
+ }
+ if (jpeg_buf[0] == 0 && jpeg_buf[1] == 0)
+ printf("[Elphel_Cam] ODD...first two bytes are zero...\n");
+ } while (jpeg_buf[0] == 0 && jpeg_buf[1] == 0);
+ *fetch_jpeg_buf = jpeg_buf;
+ *fetch_buf_size = jpeg_file_size;
+ return true;
+}
+
+
+bool Elphel_Cam::config_cmd(string url, string cmd)
+{
+ config_ss_mutex.lock();
+ config_ss.clear(); // reset stringstream state so we can insert into it again
+ config_ss.str("");
+ config_ss_mutex.unlock();
+
+ ostringstream oss;
+ oss << url << cmd;
+
+ char urlbuf[512];
+ strcpy(urlbuf, oss.str().c_str());
+
+ // printf("Executing command: %s\n", urlbuf);
+
+ curl_easy_setopt(config_curl, CURLOPT_URL, urlbuf);
+
+ CURLcode code;
+ if (code = curl_easy_perform(config_curl))
+ {
+ printf("woah! curl error: [%s]\n", curl_easy_strerror(code));
+ return false;
+ }
+ return true;
+}
+
+
+bool Elphel_Cam::compressor_cmd(string cmd) {
+ return config_cmd(comp_url, cmd);
+}
+
+bool Elphel_Cam::ccam_cmd(string cmd) {
+ return config_cmd(ccam_url, cmd);
+}
+
+bool Elphel_Cam::towp() {
+ return config_cmd(towp_url, string(""));
+}
+
+bool Elphel_Cam::init(float fps, int im_dec, int im_bin) {
+
+ uint8_t *jpeg;
+ uint32_t jpeg_size;
+
+ for (int i = 0; i < 2; i++) { //loop twice
+
+ if (!compressor_cmd("cmd=reset"))
+ return false;
+
+ //magic incantation:
+ //http://wiki.elphel.com/index.php?title=Ccam.cgi
+ ostringstream oss;
+ oss << "opt=vhcxyu+!-"
+ << "&dh=" << im_dec << "&dv=" << im_dec
+ << "&bh=" << im_bin << "&bh=" << im_bin
+ << "&iq=90"
+ << "&fps=" << fps << "&fpslm=3"
+ << "&kgm=6&sens=2&bit=8&gam=50&pxl=10&csb=200&csr=200&rscale=auto&bscale=auto";
+
+ if (!ccam_cmd(oss.str()))
+ return false;
+
+ if (!compressor_cmd("cmd=run"))
+ return false;
+
+ if (!towp())
+ return false;
+
+ for (int j = 0; j < 10;j++) {
+ if (!next_jpeg(&jpeg, &jpeg_size))
+ return false;
+ }
+
+ if (!compressor_cmd("cmd=stop"))
+ return false;
+ }
+
+ return true;
+
+}
+
+
+bool Elphel_Cam::start() {
+ if (!compressor_cmd("cmd=run"))
+ return false;
+
+ if (!towp())
+ return false;
+
+ return true;
+
+}
+
+bool Elphel_Cam::stop() {
+ return compressor_cmd("cmd=stop");
+}
+
+
+size_t Elphel_Cam::jpeg_write(void *buf, size_t size, size_t nmemb, void *userp)
+{
+ if (size * nmemb == 0)
+ return 0;
+ Elphel_Cam *a = (Elphel_Cam *)userp;
+ if (a->jpeg_file_size + size*nmemb >= a->jpeg_buf_size)
+ {
+ // overalloc
+ a->jpeg_buf_size = 2 * (a->jpeg_file_size + (size*nmemb));
+ //printf("jpeg_buf_size is now %d\n", a->jpeg_buf_size);
+ if (a->jpeg_buf)
+ delete[] a->jpeg_buf;
+ a->jpeg_buf = new uint8_t[a->jpeg_buf_size];
+ }
+ memcpy(a->jpeg_buf + a->jpeg_file_size, buf, size*nmemb);
+ a->jpeg_file_size += size*nmemb;
+ return size*nmemb;
+}
+
+
+size_t Elphel_Cam::config_write(void *buf, size_t size, size_t nmemb, void *userp)
+{
+ if (size * nmemb == 0)
+ return 0;
+ Elphel_Cam *a = (Elphel_Cam *)userp;
+ a->config_ss_mutex.lock();
+ a->config_ss << string((char *)buf, size*nmemb);
+ //printf("writing %d bytes\n", size*nmemb);
+ //cout << a->ptz_ss.str() << endl;
+ a->config_ss_mutex.unlock();
+ //cout << string((char *)buf, size*nmemb);
+ return size*nmemb;
+}
Added: pkg/trunk/elphel_cam/test/test_cam/Makefile
===================================================================
--- pkg/trunk/elphel_cam/test/test_cam/Makefile (rev 0)
+++ pkg/trunk/elphel_cam/test/test_cam/Makefile 2008-04-16 01:35:21 UTC (rev 104)
@@ -0,0 +1,4 @@
+SRC = test_cam.cpp
+OUT = test_cam
+PKG = elphel_cam
+include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/node.mk
Added: pkg/trunk/elphel_cam/test/test_cam/test_cam.cpp
===================================================================
--- pkg/trunk/elphel_cam/test/test_cam/test_cam.cpp (rev 0)
+++ pkg/trunk/elphel_cam/test/test_cam/test_cam.cpp 2008-04-16 01:35:21 UTC (rev 104)
@@ -0,0 +1,64 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+#include <iostream>
+#include <fstream>
+#include "elphel_cam/elphel_cam.h"
+
+using namespace std;
+
+int main() {
+
+ Elphel_Cam e("192.168.0.9");
+
+ uint8_t* jpeg;
+ uint32_t jpeg_size;
+
+ e.init(80, 4, 4);
+
+ e.start();
+
+ for (int i = 0; i < 200;i++) {
+ ostringstream oss;
+ oss << "img" << i << ".jpg";
+
+ ofstream outfile(oss.str().c_str(),ofstream::binary);
+ e.next_jpeg(&jpeg, &jpeg_size);
+ outfile.write((char*)jpeg, jpeg_size);
+
+ outfile.close();
+ }
+
+ e.stop();
+}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-04-17 19:49:34
|
Revision: 116
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=116&view=rev
Author: gerkey
Date: 2008-04-17 12:49:41 -0700 (Thu, 17 Apr 2008)
Log Message:
-----------
copy of gmapping from openslam.org
Added Paths:
-----------
pkg/trunk/gmapping/
pkg/trunk/gmapping/Makefile
pkg/trunk/gmapping/TODO.txt
pkg/trunk/gmapping/bin/
pkg/trunk/gmapping/build_tools/
pkg/trunk/gmapping/build_tools/Makefile.app
pkg/trunk/gmapping/build_tools/Makefile.generic-shared-object
pkg/trunk/gmapping/build_tools/Makefile.subdirs
pkg/trunk/gmapping/build_tools/generate_shared_object
pkg/trunk/gmapping/build_tools/message
pkg/trunk/gmapping/build_tools/pretty_compiler
pkg/trunk/gmapping/build_tools/testlib
pkg/trunk/gmapping/carmenwrapper/
pkg/trunk/gmapping/carmenwrapper/Makefile
pkg/trunk/gmapping/carmenwrapper/carmenwrapper.cpp
pkg/trunk/gmapping/carmenwrapper/carmenwrapper.h
pkg/trunk/gmapping/configfile/
pkg/trunk/gmapping/configfile/Makefile
pkg/trunk/gmapping/configfile/configfile.cpp
pkg/trunk/gmapping/configfile/configfile.h
pkg/trunk/gmapping/configfile/configfile_test.cpp
pkg/trunk/gmapping/configfile/demo.cfg
pkg/trunk/gmapping/configfile/test.ini
pkg/trunk/gmapping/configure
pkg/trunk/gmapping/docs/
pkg/trunk/gmapping/docs/Instructions.txt
pkg/trunk/gmapping/docs/scanmatcher.tex
pkg/trunk/gmapping/docs/userver.txt
pkg/trunk/gmapping/gfs-carmen/
pkg/trunk/gmapping/gfs-carmen/Makefile
pkg/trunk/gmapping/gfs-carmen/gfs-carmen.cpp
pkg/trunk/gmapping/grid/
pkg/trunk/gmapping/grid/Makefile
pkg/trunk/gmapping/grid/accessstate.h
pkg/trunk/gmapping/grid/array2d.h
pkg/trunk/gmapping/grid/graphmap.cpp
pkg/trunk/gmapping/grid/harray2d.h
pkg/trunk/gmapping/grid/map.h
pkg/trunk/gmapping/grid/map_test.cpp
pkg/trunk/gmapping/gridfastslam/
pkg/trunk/gmapping/gridfastslam/Makefile
pkg/trunk/gmapping/gridfastslam/gfs2log.cpp
pkg/trunk/gmapping/gridfastslam/gfs2neff.cpp
pkg/trunk/gmapping/gridfastslam/gfs2rec.cpp
pkg/trunk/gmapping/gridfastslam/gfs2stat.cpp
pkg/trunk/gmapping/gridfastslam/gfs2stream.cpp
pkg/trunk/gmapping/gridfastslam/gfsreader.cpp
pkg/trunk/gmapping/gridfastslam/gfsreader.h
pkg/trunk/gmapping/gridfastslam/gridslamprocessor.cpp
pkg/trunk/gmapping/gridfastslam/gridslamprocessor.h
pkg/trunk/gmapping/gridfastslam/gridslamprocessor.hxx
pkg/trunk/gmapping/gridfastslam/gridslamprocessor_tree.cpp
pkg/trunk/gmapping/gridfastslam/motionmodel.cpp
pkg/trunk/gmapping/gridfastslam/motionmodel.h
pkg/trunk/gmapping/gui/
pkg/trunk/gmapping/gui/Makefile
pkg/trunk/gmapping/gui/gfs2img.cpp
pkg/trunk/gmapping/gui/gfs_logplayer.cpp
pkg/trunk/gmapping/gui/gfs_nogui.cpp
pkg/trunk/gmapping/gui/gfs_simplegui.cpp
pkg/trunk/gmapping/gui/gsp_thread.cpp
pkg/trunk/gmapping/gui/gsp_thread.h
pkg/trunk/gmapping/gui/qgraphpainter.cpp
pkg/trunk/gmapping/gui/qgraphpainter.h
pkg/trunk/gmapping/gui/qmappainter.cpp
pkg/trunk/gmapping/gui/qmappainter.h
pkg/trunk/gmapping/gui/qnavigatorwidget.cpp
pkg/trunk/gmapping/gui/qnavigatorwidget.h
pkg/trunk/gmapping/gui/qparticleviewer.cpp
pkg/trunk/gmapping/gui/qparticleviewer.h
pkg/trunk/gmapping/gui/qpixmapdumper.cpp
pkg/trunk/gmapping/gui/qpixmapdumper.h
pkg/trunk/gmapping/gui/qslamandnavwidget.cpp
pkg/trunk/gmapping/gui/qslamandnavwidget.h
pkg/trunk/gmapping/ini/
pkg/trunk/gmapping/ini/gfs-LMS-10cm.ini
pkg/trunk/gmapping/ini/gfs-LMS-20cm.ini
pkg/trunk/gmapping/ini/gfs-LMS-5cm.ini
pkg/trunk/gmapping/ini/gfs-PLS-10cm.ini
pkg/trunk/gmapping/ini/gfs-PLS-5cm.ini
pkg/trunk/gmapping/lib/
pkg/trunk/gmapping/log/
pkg/trunk/gmapping/log/Makefile
pkg/trunk/gmapping/log/carmenconfiguration.cpp
pkg/trunk/gmapping/log/carmenconfiguration.h
pkg/trunk/gmapping/log/configuration.cpp
pkg/trunk/gmapping/log/configuration.h
pkg/trunk/gmapping/log/log_plot.cpp
pkg/trunk/gmapping/log/log_test.cpp
pkg/trunk/gmapping/log/rdk2carmen.cpp
pkg/trunk/gmapping/log/scanstudio2carmen.cpp
pkg/trunk/gmapping/log/sensorlog.cpp
pkg/trunk/gmapping/log/sensorlog.h
pkg/trunk/gmapping/log/sensorstream.cpp
pkg/trunk/gmapping/log/sensorstream.h
pkg/trunk/gmapping/manual.mk
pkg/trunk/gmapping/manual.mk-template
pkg/trunk/gmapping/particlefilter/
pkg/trunk/gmapping/particlefilter/Makefile
pkg/trunk/gmapping/particlefilter/particlefilter.cpp
pkg/trunk/gmapping/particlefilter/particlefilter.h
pkg/trunk/gmapping/particlefilter/particlefilter_test.cpp
pkg/trunk/gmapping/particlefilter/pf.h
pkg/trunk/gmapping/particlefilter/range_bearing.cpp
pkg/trunk/gmapping/scanmatcher/
pkg/trunk/gmapping/scanmatcher/Makefile
pkg/trunk/gmapping/scanmatcher/gridlinetraversal.h
pkg/trunk/gmapping/scanmatcher/icp.h
pkg/trunk/gmapping/scanmatcher/icptest.cpp
pkg/trunk/gmapping/scanmatcher/lumiles.h
pkg/trunk/gmapping/scanmatcher/scanmatch_test.cpp
pkg/trunk/gmapping/scanmatcher/scanmatcher.cpp
pkg/trunk/gmapping/scanmatcher/scanmatcher.h
pkg/trunk/gmapping/scanmatcher/scanmatcher.new.cpp
pkg/trunk/gmapping/scanmatcher/scanmatcherprocessor.cpp
pkg/trunk/gmapping/scanmatcher/scanmatcherprocessor.h
pkg/trunk/gmapping/scanmatcher/smmap.cpp
pkg/trunk/gmapping/scanmatcher/smmap.h
pkg/trunk/gmapping/sensor/
pkg/trunk/gmapping/sensor/Makefile
pkg/trunk/gmapping/sensor/sensor_base/
pkg/trunk/gmapping/sensor/sensor_base/Makefile
pkg/trunk/gmapping/sensor/sensor_base/sensor.cpp
pkg/trunk/gmapping/sensor/sensor_base/sensor.h
pkg/trunk/gmapping/sensor/sensor_base/sensoreading.h
pkg/trunk/gmapping/sensor/sensor_base/sensorreading.cpp
pkg/trunk/gmapping/sensor/sensor_base/sensorreading.h
pkg/trunk/gmapping/sensor/sensor_odometry/
pkg/trunk/gmapping/sensor/sensor_odometry/Makefile
pkg/trunk/gmapping/sensor/sensor_odometry/odometryreading.cpp
pkg/trunk/gmapping/sensor/sensor_odometry/odometryreading.h
pkg/trunk/gmapping/sensor/sensor_odometry/odometrysensor.cpp
pkg/trunk/gmapping/sensor/sensor_odometry/odometrysensor.h
pkg/trunk/gmapping/sensor/sensor_range/
pkg/trunk/gmapping/sensor/sensor_range/Makefile
pkg/trunk/gmapping/sensor/sensor_range/rangereading.cpp
pkg/trunk/gmapping/sensor/sensor_range/rangereading.h
pkg/trunk/gmapping/sensor/sensor_range/rangesensor.cpp
pkg/trunk/gmapping/sensor/sensor_range/rangesensor.h
pkg/trunk/gmapping/setlibpath
pkg/trunk/gmapping/utils/
pkg/trunk/gmapping/utils/Makefile
pkg/trunk/gmapping/utils/autoptr.h
pkg/trunk/gmapping/utils/autoptr_test.cpp
pkg/trunk/gmapping/utils/commandline.h
pkg/trunk/gmapping/utils/datasmoother.h
pkg/trunk/gmapping/utils/dmatrix.h
pkg/trunk/gmapping/utils/gvalues.h
pkg/trunk/gmapping/utils/macro_params.h
pkg/trunk/gmapping/utils/movement.cpp
pkg/trunk/gmapping/utils/movement.h
pkg/trunk/gmapping/utils/optimizer.h
pkg/trunk/gmapping/utils/orientedboundingbox.h
pkg/trunk/gmapping/utils/orientedboundingbox.hxx
pkg/trunk/gmapping/utils/point.h
pkg/trunk/gmapping/utils/printmemusage.cpp
pkg/trunk/gmapping/utils/printmemusage.h
pkg/trunk/gmapping/utils/printpgm.h
pkg/trunk/gmapping/utils/stat.cpp
pkg/trunk/gmapping/utils/stat.h
pkg/trunk/gmapping/utils/stat_test.cpp
Added: pkg/trunk/gmapping/Makefile
===================================================================
--- pkg/trunk/gmapping/Makefile (rev 0)
+++ pkg/trunk/gmapping/Makefile 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,17 @@
+-include ./global.mk
+
+ifeq ($(CARMENSUPPORT),1)
+SUBDIRS=utils sensor log configfile scanmatcher carmenwrapper gridfastslam gui gfs-carmen
+else
+ifeq ($(MACOSX),1)
+SUBDIRS=utils sensor log configfile scanmatcher gridfastslam
+else
+SUBDIRS=utils sensor log configfile scanmatcher gridfastslam gui
+endif
+endif
+
+LDFLAGS+=
+CPPFLAGS+= -I../sensor
+
+-include ./build_tools/Makefile.subdirs
+
Added: pkg/trunk/gmapping/TODO.txt
===================================================================
--- pkg/trunk/gmapping/TODO.txt (rev 0)
+++ pkg/trunk/gmapping/TODO.txt 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,21 @@
+TODO-List for gmapping (and partly explore)
+--------------------------------------------
+
+open:
+-----
+
+1. implement a working(!) ancestry tree
+
+2. compute trajectory uncertainty based on the
+ ancestry tree formula
+
+3. possibility to choose the way the pose uncertainty
+ for a particle set is computed (grid vs set of
+ gaussians)
+
+4. Fix the NAN Problem with the pose uncertainty with gaussians
+
+done:
+-----
+
+(move the done stuff down here)
\ No newline at end of file
Added: pkg/trunk/gmapping/build_tools/Makefile.app
===================================================================
--- pkg/trunk/gmapping/build_tools/Makefile.app (rev 0)
+++ pkg/trunk/gmapping/build_tools/Makefile.app 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,80 @@
+# Makefile generico per applicazione
+#
+# Variabili:
+# APPS lista delle applicazioni
+# OBJS lista degli oggetti
+# QOBJS lista degli oggetti QT
+# LIBS librerie
+#
+# Ogni applicazione viene linkata con tutti gli oggetti
+
+export VERBOSE
+
+ifeq ($(LINUX),1)
+CPPFLAGS+=-DLINUX
+endif
+
+
+APPLICATIONS= $(foreach a, $(APPS),$(BINDIR)/$(a))
+all: $(APPLICATIONS)
+
+PACKAGE=$(notdir $(shell pwd))
+
+.SECONDARY: $(OBJS) $(QOBJS)
+.PHONY: all clean copy doc
+
+$(QOBJS): %.o: %.cpp moc_%.cpp
+ @$(MESSAGE) "Compiling (QT) $@"
+ @$(PRETTY) "$(CXX) $(CPPFLAGS) $(QT_INCLUDE) $(CXXFLAGS) -c $< -o $@"
+
+moc_%.cpp: %.h
+ @$(MESSAGE) "Generating MOC $@"
+ @$(PRETTY) "$(MOC) -i $< -o $@"
+
+# Generazione degli oggetti
+%.o: %.cpp
+ @$(MESSAGE) "Compiling $@"
+ @$(PRETTY) "$(CXX) $(CPPFLAGS) $(CXXFLAGS) -c $< -o $@"
+
+# Generazione delle applicazioni
+$(BINDIR)/%: %.cpp $(OBJS) $(QOBJS)
+ @$(MESSAGE) "Linking application `basename $@`"
+ @$(PRETTY) "$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(OBJS) $(QOBJS) $< -L$(LIBDIR) $(LIBS) -o $@"
+
+#Regole per la generazione di tabelle o altri file creati automaticamente
+table_%.cpp: gen_table_%
+ @$(MESSAGE) "Generating $@"
+ @$(PRETTY) "./$< > $@"
+
+gen_table_%: gen_table_%.cpp
+ @$(MESSAGE) "Generating $@"
+ @$(PRETTY) "$(CXX) $(CPPFLAGS) $(CXXFLAGS) $< -o $@"
+
+#Regole per la generazione delle dipendenze
+OBJDEPS=$(foreach module,$(basename $(OBJS) $(QOBJS)),$(module).d)
+
+$(OBJDEPS): %.d: %.cpp # ci va o no? %.h
+ @$(MESSAGE) "Generating dependecies $@"
+ @$(PRETTY) "$(CXX) $(CPPFLAGS) -MM -MG -MF $@ $<"
+
+ifneq ($(MAKECMDGOALS),clean)
+ifneq ($(MAKECMDGOALS),copy)
+-include $(OBJDEPS)
+endif
+endif
+
+doc:
+ rm -rf doc/$(PACKAGE)
+ifeq ($(strip $(DOCTITLE)),)
+ kdoc -L doc -d doc/$(PACKAGE) -n "Package $(PACKAGE) (lib$(PACKAGE).so)" $(HEADERS)
+else
+ kdoc -L doc -d doc/$(PACKAGE) -n "$(DOCTITLE) (lib$(PACKAGE).so)" $(HEADERS)
+endif
+
+clean:
+ @$(MESSAGE) "Cleaning $(PACKAGE)"
+ @$(PRETTY) "rm -f *.d *.o moc_*.cpp *.d core *~ table_*.cpp gen_table*[^.][^c][^p][^p] $(APPLICATIONS)"
+ @$(PRETTY) "rm -rf doc/$(PACKAGE)"
+
+copy: clean
+ tar -C .. -cvzf `date +../$(PACKAGE)-%d%b%y.tgz` $(PACKAGE)
Added: pkg/trunk/gmapping/build_tools/Makefile.generic-shared-object
===================================================================
--- pkg/trunk/gmapping/build_tools/Makefile.generic-shared-object (rev 0)
+++ pkg/trunk/gmapping/build_tools/Makefile.generic-shared-object 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,109 @@
+# Makefile generico per shared object
+export VERBOSE
+export CXX
+
+# Nome del package
+PACKAGE=$(notdir $(shell pwd))
+
+# Libreria da generare:
+# Se non si setta la variabile LIBNAME la libreria si chiama
+# come la directory
+ifndef LIBNAME
+LIBNAME=$(PACKAGE)
+endif
+
+ifeq ($(MACOSX),1)
+SONAME=$(LIBDIR)/lib$(LIBNAME).dylib
+endif
+
+ifeq ($(LINUX),1)
+SONAME=$(LIBDIR)/lib$(LIBNAME).so
+endif
+
+APPLICATIONS= $(foreach a, $(APPS),$(BINDIR)/$(a))
+INSTALL_SCRIPTS=$(foreach a, $(SCRIPTS),$(BINDIR)/$(a))
+
+all: $(SONAME) $(APPLICATIONS) $(INSTALL_SCRIPTS)
+
+.SECONDARY: $(OBJS) $(COBJS)
+.PHONY: all clean copy doc
+
+# Generazione della libreria
+$(SONAME): $(OBJS) $(COBJS)
+ @$(MESSAGE) "Creating library lib$(LIBNAME).so"
+ifeq ($(MACOSX),1)
+ @$(PRETTY) "$(CXX) $(LDFLAGS) -dynamiclib $(OBJS) $(COBJS) -L$(LIBDIR) $(LIBS) -install_name $@ -o $@"
+endif
+ifeq ($(LINUX),1)
+ @$(PRETTY) "$(CXX) $(LDFLAGS) -fPIC -shared $(OBJS) $(COBJS) -L $(LIBDIR) $(LIBS) -o $@"
+ @if ! $(PRETTY) "$(TESTLIB) $(SONAME)"; then $(MESSAGE) "Testing of $(SONAME) failed."; rm $(SONAME); exit 1; fi;
+endif
+
+# Generazione delle applicazioni
+$(BINDIR)/%: %.o $(SONAME)
+ @$(MESSAGE) "Linking application `basename "$@"`"
+ @$(PRETTY) "$(CXX) $(LDFLAGS) -L$(LIBDIR) $(LIBS) -l$(LIBNAME) $< -o $@"
+
+#Generazione dei moc files
+moc_%.cpp: %.h
+ @$(MESSAGE) "Compiling MOC $@"
+ @$(PRETTY) "$(MOC) -i $< -o $@"
+
+# Generazione degli oggetti
+%.o: %.cpp
+ @$(MESSAGE) "Compiling $<"
+ @$(PRETTY) "$(CXX) -fPIC $(CPPFLAGS) $(CXXFLAGS) -c $< -o $@"
+
+%.o: %.c
+ @$(MESSAGE) "Compiling $<"
+ @$(PRETTY) "$(CC) -fPIC $(CPPFLAGS) $(CFLAGS) -c $< -o $@"
+
+#Regole per la generazione delle dipendenze
+OBJDEPS= $(foreach module,$(basename $(OBJS)),$(module).d) $(foreach a, $(APPS),$(a).d)
+COBJDEPS=$(foreach module,$(basename $(COBJS)),$(module).d)
+
+$(OBJDEPS): %.d: %.cpp
+ @$(MESSAGE) "Generating dependencies for $<"
+ @$(PRETTY) "$(CXX) $(CPPFLAGS) -MM -MG $< -MF $@"
+
+$(COBJDEPS): %.d: %.c
+ @$(MESSAGE) "Generating dependencies for $<"
+ @$(PRETTY) "$(CC) $(CPPFLAGS) -MM -MG $< -MF $@"
+
+#HEADERS=`ls *.h`
+#PRECOMPILED_HEADERS=$(foreach file,$(basename $(HEADERS)), $(file).pch)
+
+ifneq ($(MAKECMDGOALS),clean)
+ifneq ($(MAKECMDGOALS),copy)
+ifneq ($(MAKECMDGOALS),dep)
+-include $(OBJDEPS) $(COBJDEPS)
+endif
+endif
+endif
+
+dep: $(OBJDEPS) $(COBJDEPS)
+
+
+# GLi script vengono semplicemente copiati
+$(BINDIR)/%.sh: %.sh
+ @$(MESSAGE) "Installing script `basename "$@"`"
+ @$(PRETTY) "cp $< $@"
+ @$(PRETTY) "chmod +x $@"
+
+
+#doc:
+# rm -rf doc/$(PACKAGE)
+#ifeq ($(strip $(DOCTITLE)),)
+# kdoc -L doc -d doc/$(PACKAGE) -n "Package $(PACKAGE) (lib$(PACKAGE).so)" $(HEADERS)
+#else
+# kdoc -L doc -d doc/$(PACKAGE) -n "$(DOCTITLE) (lib$(PACKAGE).so)" $(HEADERS)
+#endif
+
+
+clean:
+ @$(MESSAGE) "Cleaning $(PACKAGE)"
+ @$(PRETTY) "rm -f $(SONAME) $(APPLICATIONS)"
+ @$(PRETTY) "rm -f *.o *.d core *~ moc_*.cpp"
+
+copy: clean
+ tar -C .. -cvzf `date +../$(PACKAGE)-%d%b%y.tgz` $(PACKAGE)
Added: pkg/trunk/gmapping/build_tools/Makefile.subdirs
===================================================================
--- pkg/trunk/gmapping/build_tools/Makefile.subdirs (rev 0)
+++ pkg/trunk/gmapping/build_tools/Makefile.subdirs 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,16 @@
+export VERBOSE
+
+.PHONY: clean, all
+
+ifeq ($(VERBOSE), 0)
+QUIET=--no-print-directory
+endif
+
+all:
+ @for subdir in $(SUBDIRS); do $(MESSAGE) "Entering $$subdir."; if ! $(MAKE) $(QUIET) -C $$subdir; then $(MESSAGE) "Compilation in $$subdir failed."; exit 1; fi; done
+
+clean:
+ @for subdir in $(SUBDIRS); do $(MESSAGE) "Entering $$subdir."; $(MAKE) $(QUIET) -C $$subdir clean; done
+
+dep:
+ @for subdir in $(SUBDIRS); do $(MESSAGE) "Entering $$subdir."; $(MAKE) $(QUIET) -C $$subdir dep; done
Added: pkg/trunk/gmapping/build_tools/generate_shared_object
===================================================================
--- pkg/trunk/gmapping/build_tools/generate_shared_object (rev 0)
+++ pkg/trunk/gmapping/build_tools/generate_shared_object 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,16 @@
+#!/bin/tcsh
+
+echo decompressing file $1
+
+set FILELIST=`ar -t $1`
+echo "Object files:"
+foreach i ($FILELIST)
+ echo $i
+end
+
+echo generating $1:r.so
+
+ar -x $1
+ld -shared -o $1:r.so $FILELIST
+
+rm $FILELIST
Property changes on: pkg/trunk/gmapping/build_tools/generate_shared_object
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/gmapping/build_tools/message
===================================================================
--- pkg/trunk/gmapping/build_tools/message (rev 0)
+++ pkg/trunk/gmapping/build_tools/message 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,14 @@
+#!/bin/sh
+
+#echo "message: verbose = $VERBOSE"
+
+if ($VERBOSE)
+then
+ exit 0;
+fi
+
+a=$MAKELEVEL
+
+while ((0<$a)); do echo -n " "; let "a = $a - 1";done
+
+echo $1
Property changes on: pkg/trunk/gmapping/build_tools/message
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/gmapping/build_tools/pretty_compiler
===================================================================
--- pkg/trunk/gmapping/build_tools/pretty_compiler (rev 0)
+++ pkg/trunk/gmapping/build_tools/pretty_compiler 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,26 @@
+#!/bin/sh
+
+
+#echo "pretty: verbose = $VERBOSE"
+
+if ($VERBOSE)
+then
+ echo $1;
+ if ! eval $1
+ then
+ echo "Failed command was:"
+ echo $1
+ echo "in directory " `pwd`
+ exit 1
+ fi
+else
+ if ! eval $1
+ then
+ echo "Failed command was:"
+ echo $1
+ echo "in directory " `pwd`
+ exit 1
+ fi
+fi
+
+exit 0
Property changes on: pkg/trunk/gmapping/build_tools/pretty_compiler
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/gmapping/build_tools/testlib
===================================================================
--- pkg/trunk/gmapping/build_tools/testlib (rev 0)
+++ pkg/trunk/gmapping/build_tools/testlib 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,23 @@
+#!/bin/bash
+if [ -z "$1" ]; then
+ echo "Syntax: rtestlib <library>"
+ exit 1
+fi
+FNAME=`mktemp rtestlibXXXXXX`
+echo "int main() { return 0; }" > $FNAME.cpp
+
+g++ $1 $FNAME.cpp -o $FNAME
+result=$?
+rm -f $FNAME.cpp $FNAME
+
+exit $result
+
+#if g++ $1 $FNAME.cpp -o $FNAME
+#then#
+# rm -f $FNAME.cpp $FNAME
+# exit 1
+#else
+# rm -f $FNAME.cpp $FNAME
+# exit 0
+#fi
+
Property changes on: pkg/trunk/gmapping/build_tools/testlib
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/gmapping/carmenwrapper/Makefile
===================================================================
--- pkg/trunk/gmapping/carmenwrapper/Makefile (rev 0)
+++ pkg/trunk/gmapping/carmenwrapper/Makefile 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,14 @@
+OBJS= carmenwrapper.o
+APPS=
+
+LIBS+= -L$(CARMEN_HOME)/lib -lnavigator_interface -lsimulator_interface -lrobot_interface -llaser_interface -lparam_interface -lglobal -lipc -lm -lutils -lsensor_range -llog -lscanmatcher -lpthread -lz
+CPPFLAGS+=-I../sensor -I$(CARMEN_HOME)/include
+
+-include ../global.mk
+
+ifeq ($(CARMENSUPPORT), 0)
+OBJS=
+ -include ../build_tools/Makefile.app
+else
+ -include ../build_tools/Makefile.generic-shared-object
+endif
Added: pkg/trunk/gmapping/carmenwrapper/carmenwrapper.cpp
===================================================================
--- pkg/trunk/gmapping/carmenwrapper/carmenwrapper.cpp (rev 0)
+++ pkg/trunk/gmapping/carmenwrapper/carmenwrapper.cpp 2008-04-17 19:49:41 UTC (rev 116)
@@ -0,0 +1,490 @@
+/*****************************************************************
+ *
+ * This file is part of the GMAPPING project
+ *
+ * GMAPPING Copyright (c) 2004 Giorgio Grisetti,
+ * Cyrill Stachniss, and Wolfram Burgard
+ *
+ * This software is licensed under the "Creative Commons
+ * License (Attribution-NonCommercial-ShareAlike 2.0)"
+ * and is copyrighted by Giorgio Grisetti, Cyrill Stachniss,
+ * and Wolfram Burgard.
+ *
+ * Further information on this license can be found at:
+ * http://creativecommons.org/licenses/by-nc-sa/2.0/
+ *
+ * GMAPPING is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE.
+ *
+ *****************************************************************/
+
+
+#include "carmenwrapper.h"
+
+using namespace GMapping;
+using namespace std;
+
+//static vars for the carmenwrapper
+SensorMap CarmenWrapper::m_sensorMap;
+deque<RangeReading> CarmenWrapper::m_rangeDeque;
+pthread_mutex_t CarmenWrapper::m_mutex;
+sem_t CarmenWrapper::m_dequeSem;
+pthread_mutex_t CarmenWrapper::m_lock;
+pthread_t CarmenWrapper::m_readingThread;
+RangeSensor* CarmenWrapper::m_frontLaser=0;
+RangeSensor* CarmenWrapper::m_rearLaser=0;
+bool CarmenWrapper::m_threadRunning=false;
+OrientedPoint CarmenWrapper::m_truepos;
+bool CarmenWrapper::stopped=true;
+
+
+void CarmenWrapper::initializeIPC(const char* name) {
+ carmen_ipc_initialize(1,(char **)&name);
+}
+
+
+
+
+int CarmenWrapper::registerLocalizationMessages(){
+ lock();
+ IPC_RETURN_TYPE err;
+
+ /* register globalpos message */
+ err = IPC_defineMsg(CARMEN_LOCALIZE_GLOBALPOS_NAME, IPC_VARIABLE_LENGTH,
+ CARMEN_LOCALIZE_GLOBALPOS_FMT);
+ carmen_test_ipc_exit(err, "Could not define", CARMEN_LOCALIZE_GLOBALPOS_NAME);
+
+ /* register robot particle message */
+ err = IPC_defineMsg(CARMEN_LOCALIZE_PARTICLE_NAME, IPC_VARIABLE_LENGTH,
+ CARMEN_LOCALIZE_PARTICLE_FMT);
+ carmen_test_ipc_exit(err, "Could not define", CARMEN_LOCALIZE_PARTICLE_NAME);
+
+/*
+ carmen_localize_subscribe_initialize_placename_message(NULL,
+ (carmen_handler_t)
+ carmen_localize_initialize_placename_handler,
+ CARMEN_SUBSCRIBE_LATEST);
+
+ // register map request message
+ err = IPC_defineMsg(CARMEN_LOCALIZE_MAP_QUERY_NAME, IPC_VARIABLE_LENGTH,
+ CARMEN_LOCALIZE_MAP_QUERY_FMT);
+ carmen_test_ipc_exit(err, "Could not define",
+ CARMEN_LOCALIZE_MAP_QUERY_NAME);
+
+ err = IPC_defineMsg(CARMEN_LOCALIZE_MAP_NAME, IPC_VARIABLE_LENGTH,
+ CARMEN_LOCALIZE_MAP_FMT);
+ carmen_test_ipc_exit(err, "Could not define", CARMEN_LOCALIZE_MAP_NAME);
+
+ // subscribe to map request message
+ err = IPC_subscribe(CARMEN_LOCALIZE_MAP_QUERY_NAME, map_query_handler, NULL);
+ carmen_test_ipc(err, "Could not subscribe", CARMEN_LOCALIZE_MAP_QUERY_NAME);
+ IPC_setMsgQueueLength(CARMEN_LOCALIZE_MAP_QUERY_NAME, 1);
+
+
+ // register globalpos request message
+ err = IPC_defineMsg(CARMEN_LOCALIZE_GLOBALPOS_QUERY_NAME,
+ IPC_VARIABLE_LENGTH,
+ CARMEN_DEFAULT_MESSAGE_FMT);
+ carmen_test_ipc_exit(err, "Could not define",
+ CARMEN_LOCALIZE_MAP_QUERY_NAME);
+
+ // subscribe to globalpos request message
+ err = IPC_subscribe(CARMEN_LOCALIZE_GLOBALPOS_QUERY_NAME,
+ globalpos_query_handler, NULL);
+ carmen_test_ipc(err, "Could not subscribe",
+ CARMEN_LOCALIZE_GLOBALPOS_QUERY_NAME);
+ IPC_setMsgQueueLength(CARMEN_LOCALIZE_GLOBALPOS_QUERY_NAME, 1);
+*/
+ unlock();
+ return 0;
+}
+
+bool CarmenWrapper::start(const char* name){
+ if (m_threadRunning)
+ return false;
+ carmen_robot_subscribe_frontlaser_message(NULL, (carmen_handler_t)robot_frontlaser_handler, CARMEN_SUBSCRIBE_LATEST);
+ carmen_robot_subscribe_rearlaser_message(NULL, (carmen_handler_t)robot_rearlaser_handler, CARMEN_SUBSCRIBE_LATEST);
+ carmen_simulator_subscribe_truepos_message(NULL,(carmen_handler_t) simulator_truepos_handler, CARMEN_SUBSCRIBE_LATEST);
+
+ IPC_RETURN_TYPE err;
+
+ err = IPC_subscribe(CARMEN_NAVIGATOR_GO_NAME, navigator_go_handler, NULL);
+ carmen_test_ipc_exit(err, "Could not subscribe",
+ CARMEN_NAVIGATOR_GO_NAME);
+ IPC_setMsgQueueLength(CARMEN_NAVIGATOR_GO_NAME, 1);
+
+ err = IPC_subscribe(CARMEN_NAVIGATOR_STOP_NAME, navigator_stop_handler, NULL);
+ carmen_test_ipc_exit(err, "Could not subscribe",
+ CARMEN_NAVIGATOR_STOP_NAME);
+ IPC_setMsgQueueLength(CARMEN_NAVIGATOR_STOP_NAME, 1);
+
+
+
+ signal(SIGINT, shutdown_module);
+ pthread_mutex_init(&m_mutex, 0);
+ pthread_mutex_init(&m_lock, 0);
+ sem_init(&m_dequeSem, 0, 0);
+ m_threadRunning=true;
+ pthread_create (&m_readingThread,0,m_reading_function,0);
+ return true;
+}
+
+void CarmenWrapper::lock(){
+ //cerr <<"LOCK" << endl;
+ pthread_mutex_lock(&m_lock);
+}
+
+void CarmenWrapper::unlock(){
+ //cerr <<"UNLOCK" << endl;
+ pthread_mutex_unlock(&m_lock);
+}
+
+
+bool CarmenWrapper::sensorMapComputed(){
+ pthread_mutex_lock(&m_mutex);
+ bool smok=m_frontLaser;
+ pthread_mutex_unlock(&m_mutex);
+ return smok;
+}
+
+const SensorMap& CarmenWrapper::sensorMap(){
+ return m_sensorMap;
+}
+
+bool CarmenWrapper::isRunning(){
+ return m_threadRunning;
+}
+
+bool CarmenWrapper::isStopped(){
+ return stopped;
+}
+
+int CarmenWrapper::queueLength(){
+ int ql=0;
+ pthread_mutex_lock(&m_mutex);
+ ql=m_rangeDeque.size();
+ pthread_mutex_unlock(&m_mutex);
+ return ql;
+}
+
+OrientedPoint CarmenWrapper::getTruePos(){
+ return m_truepos;
+}
+
+bool CarmenWrapper::getReading(RangeReading& reading){
+ bool present=false;
+ sem_wait(&m_dequeSem);
+ pthread_mutex_lock(&m_mutex);
+ if (!m_rangeDeque.empty()){
+// cerr << __PRETTY_FUNCTION__ << ": queue size=" <<m_rangeDeque.size() << endl;
+ reading=m_rangeDeque.front();
+ m_rangeDeque.pop_front();
+ present=true;
+ }
+ int sval;
+ sem_getvalue(&m_dequeSem,&sval);
+// cerr << "fetch. elements= "<< m_rangeDeque.size() << " sval=" << sval <<endl;
+ pthread_mutex_unlock(&m_mutex);
+ return present;
+}
+
+void CarmenWrapper::addReading(RangeReading& reading){
+ pthread_mutex_lock(&m_mutex);
+ m_rangeDeque.push_back(reading);
+ pthread_mutex_unlock(&m_mutex);
+ sem_post(&m_dequeSem);
+ int sval;
+ sem_getvalue(&m_dequeSem,&sval);
+// cerr << "post. elements= "<< m_rangeDeque.size() << " sval=" << sval <<endl;
+}
+
+
+//RangeSensor::RangeSensor(std::string name, unsigned int beams_num, unsigned int res, const OrientedPoint& position, double span, double maxrange):
+
+void CarmenWrapper::robot_frontlaser_handler(carmen_robot_laser_message* frontlaser) {
+/* if (! m_rangeSensor){
+ double res=0;
+ if (frontlaser->num_readings==180 || frontlaser->num_readings==181)
+ res=M_PI/180;
+ if (frontlaser->num_readings==360 || frontlaser->num_readings==361)
+ res=M_PI/360;
+ assert(res>0);
+ m_rangeSensor=new RangeSensor("FLASER",frontlaser->num_readings, res, OrientedPoint(0,0,0), 0, 89.9);
+ m_sensorMap.insert(make_pair(string("FLASER"), m_rangeSensor));
+
+ cout << __PRETTY_FUNCTION__
+ << ": FrontLaser configured."
+ << " Readings " << m_rangeSensor->beams().size()
+ << " Resolution " << res << endl;
+ }
+
+ RangeReading reading(m_rangeSensor, frontlaser->timestamp);
+ reading.resize(m_rangeSensor->beams().size());
+ for (unsigned int i=0; i< (unsigned int)frontlaser->num_readings; i++){
+ reading[i]=(double)frontlaser->range[i];
+ }
+ reading.setPose(OrientedPoint(frontlaser->x, frontlaser->y, frontlaser->theta));
+*/
+ RangeReading reading=carmen2reading(*frontlaser);
+ addReading(reading);
+}
+
+void CarmenWrapper::robot_rearlaser_handler(carmen_robot_laser_message* rearlaser) {
+/* if (! m_rangeSensor){
+ double res=0;
+ if (frontlaser->num_readings==180 || frontlaser->num_readings==181)
+ res=M_PI/180;
+ if (frontlaser->num_readings==360 || frontlaser->num_readings==361)
+ res=M_PI/360;
+ assert(res>0);
+ m_rangeSensor=new RangeSensor("FLASER",frontlaser->num_readings, res, OrientedPoint(0,0,0), 0, 89.9);
+ m_sensorMap.insert(make_pair(string("FLASER"), m_rangeSensor));
+
+ cout << __PRETTY_FUNCTION__
+ << ": FrontLaser configured."
+ << " Readings " << m_rangeSensor->beams().size()
+ << " Resolution " << res << endl;
+ }
+
+ RangeReading reading(m_rangeSensor, frontlaser->timestamp);
+ reading.resize(m_rangeSensor->beams().size());
+ for (unsigned int i=0; i< (unsigned int)frontlaser->num_readings; i++){
+ reading[i]=(double)frontlaser->range[i];
+ }
+ reading.setPose(OrientedPoint(frontlaser->x, frontlaser->y, frontlaser->theta));
+*/
+ RangeReading reading=carmen2reading(*rearlaser);
+ addReading(reading);
+}
+
+
+
+
+void CarmenWrapper:: navigator_go_handler(MSG_INSTANCE msgRef, BYTE_ARRAY callData, void*) {
+ carmen_navigator_go_message msg;
+ FORMATTER_PTR formatter;
+ IPC_RETURN_TYPE err;
+
+ formatter = IPC_msgInstanceFormatter(msgRef);
+ err = IPC_unmarshallData(formatter, callData, &msg,
+ sizeof(carmen_navigator_go_message));
+ IPC_freeByteArray(callData);
+
+ carmen_test_ipc_return
+ (err, "Could not unmarshall", IPC_msgInstanceName(msgRef));
+ cerr<<"go"<<endl;
+ stopped=false;
+}
+
+
+void CarmenWrapper:: navigator_stop_handler(MSG_INSTANCE msgRef, BYTE_ARRAY callData, void*) {
+ carmen_navigator_stop_message msg;
+ FORMATTER_PTR formatter;
+ IPC_RETURN_TYPE err;
+
+ formatter = IPC_msgInstanceFormatter(msgRef);
+ err = IPC_unmarshallData(formatter, callData, &msg,
+ sizeof(carmen_navigator_stop_message));
+ IPC_freeByteArray(callData);
+
+ carmen_test_ipc_return
+ (err, "Could not unmarshall", IPC_msgInstanceName(msgRef));
+ cerr<<"stop"<<endl;
+ stopped=true;
+}
+
+
+
+void CarmenWrapper::simulator_truepos_handler(carmen_simulator_truepos_message* truepos){
+ m_truepos.x=truepos->truepose.x;
+ m_truepos.y=truepos->truepose.y;
+ m_truepos.theta=truepos->truepose.theta;
+}
+
+RangeReading CarmenWrapper::carmen2reading(const carmen_robot_laser_message& msg){
+ //either front laser or rear laser
+ double dth=msg.laser_pose.theta-msg.robot_pose.theta;
+ dth=atan2(sin(dth), cos(dth));
+
+ if (msg.laser_pose.theta==msg.robot_pose.theta && !m_frontLaser){
+ double res=0;
+ res = msg.config.angular_resolution;
+// if (msg.num_readings==180 || msg.num_readings==181)
+// res=M_PI/180;
+// if (msg.num_readings==360 || msg.num_readings==361)
+// res=M_PI/360;
+ assert(res>0);
+ string sensorName="FLASER";
+ OrientedPoint rpose(msg.robot_pose.x, msg.robot_pose.y, msg.robot_pose.theta);
+ OrientedPoint lpose(msg.laser_pose.x, msg.laser_pose.y, msg.laser_pose.theta);
+ OrientedPoint dp=absoluteDifference(lpose, rpose);
+ m_frontLaser=new RangeSensor(sensorName,msg.num_readings, res, OrientedPoint(0,0,msg...
[truncated message content] |
|
From: <jl...@us...> - 2008-04-18 02:26:51
|
Revision: 133
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=133&view=rev
Author: jleibs
Date: 2008-04-17 19:26:07 -0700 (Thu, 17 Apr 2008)
Log Message:
-----------
Simple node using Morgans point cloud viewer to view laser data.
Modified Paths:
--------------
pkg/trunk/camera_calibration/src/calibrator/calibrator.cpp
pkg/trunk/etherdrive/build.yaml
pkg/trunk/etherdrive/manifest.xml
pkg/trunk/etherdrive/src/libetherdrive/etherdrive.cpp
Added Paths:
-----------
pkg/trunk/laser_viewer/
pkg/trunk/laser_viewer/build.yaml
pkg/trunk/laser_viewer/manifest.xml
pkg/trunk/laser_viewer/nodes/
pkg/trunk/laser_viewer/nodes/laser_viewer.log
pkg/trunk/laser_viewer/nodes/run_viewer
pkg/trunk/laser_viewer/rosbuild
pkg/trunk/laser_viewer/src/
pkg/trunk/laser_viewer/src/laser_viewer/
pkg/trunk/laser_viewer/src/laser_viewer/Makefile
pkg/trunk/laser_viewer/src/laser_viewer/laser_viewer.cpp
Modified: pkg/trunk/camera_calibration/src/calibrator/calibrator.cpp
===================================================================
--- pkg/trunk/camera_calibration/src/calibrator/calibrator.cpp 2008-04-18 02:14:17 UTC (rev 132)
+++ pkg/trunk/camera_calibration/src/calibrator/calibrator.cpp 2008-04-18 02:26:07 UTC (rev 133)
@@ -91,6 +91,8 @@
char dir_name[256];
+ CvPoint2D32f* last_corners;
+
Calibrator() : ROS_Slave()
{
register_sink(image_in = new FlowImage("image_in"), ROS_CALLBACK(Calibrator, image_received));
@@ -138,6 +140,8 @@
if (mkdir(dir_name, 0755)) {
std::cout << "Failed to make directory: " << dir_name;
}
+
+ last_corners = new CvPoint2D32f[12*12];
}
virtual ~Calibrator() { }
@@ -312,6 +316,22 @@
take_pic = false;
}
+ float maxdiff = 0;
+
+ for(int c=0; c<12*12; c++) {
+ float diff = sqrt( pow(corners[c].x - last_corners[c].x, 2.0) +
+ pow(corners[c].y - last_corners[c].y, 2.0));
+ last_corners[c].x = corners[c].x;
+ last_corners[c].y = corners[c].y;
+
+ if (diff > maxdiff) {
+ maxdiff = diff;
+ }
+ }
+
+ printf("Max diff: %g\n", maxdiff);
+
+
cvDrawChessboardCorners(cvimage_bgr, board_sz, corners, corner_count, found);
if (undistort) {
Modified: pkg/trunk/etherdrive/build.yaml
===================================================================
--- pkg/trunk/etherdrive/build.yaml 2008-04-18 02:14:17 UTC (rev 132)
+++ pkg/trunk/etherdrive/build.yaml 2008-04-18 02:26:07 UTC (rev 133)
@@ -1,5 +1,6 @@
cpp:
make:
- src/libetherdrive
- - test
+ - src/etherdrive_control
+ - test/test_etherdrive
Modified: pkg/trunk/etherdrive/manifest.xml
===================================================================
--- pkg/trunk/etherdrive/manifest.xml 2008-04-18 02:14:17 UTC (rev 132)
+++ pkg/trunk/etherdrive/manifest.xml 2008-04-18 02:26:07 UTC (rev 133)
@@ -11,5 +11,6 @@
<url>http://pr.willowgarage.com</url>
<depend package='roscpp'/>
<depend package='common_flows'/>
+<depend package='unstable_flows'/>
<repository>http://pr.willowgarage.com/repos</repository>
</package>
Modified: pkg/trunk/etherdrive/src/libetherdrive/etherdrive.cpp
===================================================================
--- pkg/trunk/etherdrive/src/libetherdrive/etherdrive.cpp 2008-04-18 02:14:17 UTC (rev 132)
+++ pkg/trunk/etherdrive/src/libetherdrive/etherdrive.cpp 2008-04-18 02:26:07 UTC (rev 133)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-#include "etherdrive.h"
+#include "etherdrive/etherdrive.h"
EtherDrive::EtherDrive()
{
Added: pkg/trunk/laser_viewer/build.yaml
===================================================================
--- pkg/trunk/laser_viewer/build.yaml (rev 0)
+++ pkg/trunk/laser_viewer/build.yaml 2008-04-18 02:26:07 UTC (rev 133)
@@ -0,0 +1,3 @@
+cpp:
+ make:
+ - src/laser_viewer
\ No newline at end of file
Added: pkg/trunk/laser_viewer/manifest.xml
===================================================================
--- pkg/trunk/laser_viewer/manifest.xml (rev 0)
+++ pkg/trunk/laser_viewer/manifest.xml 2008-04-18 02:26:07 UTC (rev 133)
@@ -0,0 +1,14 @@
+<package>
+<description brief="Use the cloud viewer to display laster data.">
+
+</description>
+<author>Jeremy Leibs (email: le...@wi...)</author>
+<license>BSD</license>
+<url>http://pr.willowgarage.com</url>
+<depend package="common_flows"/>
+<depend package="hokuyourg_player"/>
+<depend package="cloud_viewer"/>
+<sys_depend lib="GL"/>
+<sys_depend lib="GLU"/>
+</package>
+
Added: pkg/trunk/laser_viewer/nodes/laser_viewer.log
===================================================================
--- pkg/trunk/laser_viewer/nodes/laser_viewer.log (rev 0)
+++ pkg/trunk/laser_viewer/nodes/laser_viewer.log 2008-04-18 02:26:07 UTC (rev 133)
@@ -0,0 +1,5 @@
+0.000987 ROS_PORT = 0
+0.001046 starting abyss XMLRPC server on port 32900
+0.011219 calling registerNode on master at http://127.0.1.1:11311/
+0.011307 sending port = 32900 to registerNode
+0.011782 TCPROS server up and running on port 34990
Added: pkg/trunk/laser_viewer/nodes/run_viewer
===================================================================
--- pkg/trunk/laser_viewer/nodes/run_viewer (rev 0)
+++ pkg/trunk/laser_viewer/nodes/run_viewer 2008-04-18 02:26:07 UTC (rev 133)
@@ -0,0 +1,8 @@
+#!/usr/bin/env ruby
+require "#{`#{ENV['ROS_ROOT']}/rospack latest yamlgraph`}/lib/yamlgraph/ygl.rb"
+g = YAMLGraph.new
+g.node 'laser_viewer/laser_viewer', {'launch'=>'xterm'}
+g.node 'hokuyourg_player/hokuyourg_player'#, {'launch'=>'xterm'}
+g.flow 'hokuyourg_player:scans', 'laser_viewer:scans'
+YAMLGraphLauncher.new.launch g
+
Property changes on: pkg/trunk/laser_viewer/nodes/run_viewer
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/laser_viewer/rosbuild
===================================================================
--- pkg/trunk/laser_viewer/rosbuild (rev 0)
+++ pkg/trunk/laser_viewer/rosbuild 2008-04-18 02:26:07 UTC (rev 133)
@@ -0,0 +1,2 @@
+#!/usr/bin/env ruby
+exec("#{`#{ENV['ROS_ROOT']}/rospack find rostools`}/scripts/yamlbuild", 'build.yaml', *ARGV)
Property changes on: pkg/trunk/laser_viewer/rosbuild
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/laser_viewer/src/laser_viewer/Makefile
===================================================================
--- pkg/trunk/laser_viewer/src/laser_viewer/Makefile (rev 0)
+++ pkg/trunk/laser_viewer/src/laser_viewer/Makefile 2008-04-18 02:26:07 UTC (rev 133)
@@ -0,0 +1,4 @@
+SRC = laser_viewer.cpp
+OUT = ../../nodes/laser_viewer
+PKG = laser_viewer
+include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/node.mk
Added: pkg/trunk/laser_viewer/src/laser_viewer/laser_viewer.cpp
===================================================================
--- pkg/trunk/laser_viewer/src/laser_viewer/laser_viewer.cpp (rev 0)
+++ pkg/trunk/laser_viewer/src/laser_viewer/laser_viewer.cpp 2008-04-18 02:26:07 UTC (rev 133)
@@ -0,0 +1,161 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+#include "ros/ros_slave.h"
+#include "common_flows/FlowLaserScan.h"
+#include "cloud_viewer/cloud_viewer.h"
+#include <SDL/SDL.h>
+#include "math.h"
+
+class Laser_Viewer : public ROS_Slave
+{
+public:
+ FlowLaserScan *laser;
+ CloudViewer *cloud_viewer;
+
+ Laser_Viewer() : ROS_Slave(), cloud_viewer(NULL)
+ {
+ register_sink(laser = new FlowLaserScan("scans"), ROS_CALLBACK(Laser_Viewer, cloud_callback));
+
+ cloud_viewer = new CloudViewer;
+
+ register_with_master();
+ }
+
+ virtual ~Laser_Viewer()
+ {
+ if (cloud_viewer)
+ delete cloud_viewer;
+ }
+
+
+ void refresh() {
+ // SDL (and Xlib) don't handle threads well, so we do both of these
+ check_keyboard();
+ display_image();
+ }
+
+ void check_keyboard() {
+ SDL_Event event;
+ while(SDL_PollEvent(&event))
+ {
+ switch(event.type)
+ {
+ case SDL_MOUSEMOTION:
+ cloud_viewer->mouse_motion(event.motion.x, event.motion.y, event.motion.xrel, event.motion.yrel);
+ cloud_viewer->render();
+ SDL_GL_SwapBuffers();
+ break;
+ case SDL_MOUSEBUTTONDOWN:
+ case SDL_MOUSEBUTTONUP:
+ {
+ int button = -1;
+ switch(event.button.button)
+ {
+ case SDL_BUTTON_LEFT: button = 0; break;
+ case SDL_BUTTON_MIDDLE: button = 1; break;
+ case SDL_BUTTON_RIGHT: button = 2; break;
+ }
+ cloud_viewer->mouse_button(event.button.x, event.button.y,
+ button, (event.type == SDL_MOUSEBUTTONDOWN ? true : false));
+ break;
+ }
+ case SDL_KEYDOWN:
+ cloud_viewer->keypress(event.key.keysym.sym);
+ cloud_viewer->render();
+ SDL_GL_SwapBuffers();
+ break;
+ }
+ }
+ }
+
+ void display_image() {
+ cloud_viewer->render();
+ SDL_GL_SwapBuffers();
+ }
+
+
+ bool sdl_init()
+ {
+ SDL_GL_SetAttribute(SDL_GL_DEPTH_SIZE, 24);
+ SDL_GL_SetAttribute(SDL_GL_DOUBLEBUFFER, 1);
+ const int w = 640, h = 480;
+ if (SDL_SetVideoMode(w, h, 32, SDL_OPENGL | SDL_HWSURFACE) == 0) {
+ fprintf(stderr, "setvideomode failed: %s\n", SDL_GetError());
+ return false;
+ }
+
+ cloud_viewer->set_opengl_params(w,h);
+
+ SDL_EnableKeyRepeat(SDL_DEFAULT_REPEAT_DELAY, SDL_DEFAULT_REPEAT_INTERVAL);//People expect Key Repeat
+
+ return true;
+ }
+
+ void cloud_callback()
+ {
+ cloud_viewer->clear_cloud();
+ for (int i = 0; i < laser->get_ranges_size(); i++) {
+ cloud_viewer->add_point(0,
+ cos(laser->angle_min + i*laser->angle_increment) * laser->ranges[i],
+ sin(laser->angle_min + i*laser->angle_increment) * laser->ranges[i],
+ 255,255,255);
+ }
+ }
+};
+
+int main(int argc, char **argv)
+{
+ if (SDL_Init(SDL_INIT_VIDEO) < 0)
+ {
+ fprintf(stderr, "SDL initialization error: %s\n", SDL_GetError());
+ exit(1);
+ }
+ atexit(SDL_Quit);
+
+ Laser_Viewer lv;
+
+ if (!lv.sdl_init())
+ {
+ fprintf(stderr, "SDL video startup error: %s\n", SDL_GetError());
+ exit(1);
+ }
+
+ while (lv.happy()) {
+ lv.refresh();
+ usleep(1000);
+ }
+ return 0;
+}
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2008-04-18 21:26:02
|
Revision: 140
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=140&view=rev
Author: jleibs
Date: 2008-04-18 14:26:05 -0700 (Fri, 18 Apr 2008)
Log Message:
-----------
This is a template stripped down package that is useful to copy and build off of.
Added Paths:
-----------
pkg/trunk/cpp_template/
pkg/trunk/cpp_template/build.yaml
pkg/trunk/cpp_template/manifest.xml
pkg/trunk/cpp_template/nodes/
pkg/trunk/cpp_template/nodes/launch_template
pkg/trunk/cpp_template/rosbuild
pkg/trunk/cpp_template/src/
pkg/trunk/cpp_template/src/template/
pkg/trunk/cpp_template/src/template/Makefile
pkg/trunk/cpp_template/src/template/template.cpp
Added: pkg/trunk/cpp_template/build.yaml
===================================================================
--- pkg/trunk/cpp_template/build.yaml (rev 0)
+++ pkg/trunk/cpp_template/build.yaml 2008-04-18 21:26:05 UTC (rev 140)
@@ -0,0 +1,3 @@
+cpp:
+ make:
+ - src/template
\ No newline at end of file
Added: pkg/trunk/cpp_template/manifest.xml
===================================================================
--- pkg/trunk/cpp_template/manifest.xml (rev 0)
+++ pkg/trunk/cpp_template/manifest.xml 2008-04-18 21:26:05 UTC (rev 140)
@@ -0,0 +1,13 @@
+<package>
+<description brief="The simplest possible package">
+
+Until CPP scaffolder is working, this will do the trick.
+
+</description>
+<author>W.G. Arage</author>
+<license>BSD</license>
+<url>http://pr.willowgarage.com</url>
+<depend package="roscpp"/>
+<depend package="common_flows"/>
+</package>
+
Added: pkg/trunk/cpp_template/nodes/launch_template
===================================================================
--- pkg/trunk/cpp_template/nodes/launch_template (rev 0)
+++ pkg/trunk/cpp_template/nodes/launch_template 2008-04-18 21:26:05 UTC (rev 140)
@@ -0,0 +1,8 @@
+#!/usr/bin/env ruby
+require "#{`#{ENV['ROS_ROOT']}/rospack latest yamlgraph`}/lib/yamlgraph/ygl.rb"
+g = YAMLGraph.new
+g.param 'template.some_param', '1.234'
+g.node 'cpp_template/template', {'launch'=>'xterm'}
+g.flow 'template:float_out', 'template:float_in'
+YAMLGraphLauncher.new.launch g
+
Property changes on: pkg/trunk/cpp_template/nodes/launch_template
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/cpp_template/rosbuild
===================================================================
--- pkg/trunk/cpp_template/rosbuild (rev 0)
+++ pkg/trunk/cpp_template/rosbuild 2008-04-18 21:26:05 UTC (rev 140)
@@ -0,0 +1,2 @@
+#!/usr/bin/env ruby
+exec("#{`#{ENV['ROS_ROOT']}/rospack find rostools`}/scripts/yamlbuild", 'build.yaml', *ARGV)
Property changes on: pkg/trunk/cpp_template/rosbuild
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/cpp_template/src/template/Makefile
===================================================================
--- pkg/trunk/cpp_template/src/template/Makefile (rev 0)
+++ pkg/trunk/cpp_template/src/template/Makefile 2008-04-18 21:26:05 UTC (rev 140)
@@ -0,0 +1,4 @@
+SRC = template.cpp
+OUT = ../../nodes/template
+PKG = cpp_template
+include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/node.mk
Added: pkg/trunk/cpp_template/src/template/template.cpp
===================================================================
--- pkg/trunk/cpp_template/src/template/template.cpp (rev 0)
+++ pkg/trunk/cpp_template/src/template/template.cpp 2008-04-18 21:26:05 UTC (rev 140)
@@ -0,0 +1,82 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+#include "ros/ros_slave.h"
+#include "common_flows/FlowFloat32.h"
+
+class TemplateNode : public ROS_Slave
+{
+public:
+ FlowFloat32 *float_in;
+ FlowFloat32 *float_out;
+
+ double param;
+
+ TemplateNode() : ROS_Slave()
+ {
+ register_source(float_out = new FlowFloat32("float_out"));
+ register_sink(float_in = new FlowFloat32("float_in"), ROS_CALLBACK(TemplateNode, float_callback));
+ register_with_master();
+ if (!get_double_param(".some_param", ¶m))
+ param = 0;
+ printf("package path is [%s]\n", get_my_package_path().c_str());
+ }
+
+ virtual ~TemplateNode()
+ {
+
+ }
+
+ void float_callback() {
+ printf("Look, I got my own value: %g\n", float_in->data);
+ }
+
+ void publish_float() {
+ float_out->data = param;
+ float_out->publish();
+ }
+
+
+};
+
+int main(int argc, char **argv)
+{
+ TemplateNode a;
+ while (a.happy()) {
+ a.publish_float();
+ usleep(1000);
+ }
+ return 0;
+}
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mor...@us...> - 2008-04-22 23:58:19
|
Revision: 160
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=160&view=rev
Author: morgan_quigley
Date: 2008-04-22 16:58:24 -0700 (Tue, 22 Apr 2008)
Log Message:
-----------
slowly i will move the packages to correpond to the 'code forest' style of organization instead of the current 'pile of directories' setup
Modified Paths:
--------------
pkg/trunk/axis_cam/nodes/test_axis_cam
pkg/trunk/cloud_viewer/src/standalone/Makefile
Added Paths:
-----------
pkg/trunk/3rdparty/
pkg/trunk/3rdparty/sdl/
pkg/trunk/3rdparty/sdl/Makefile
pkg/trunk/3rdparty/sdl/SDL-1.2.13.tar.gz
pkg/trunk/3rdparty/sdl/manifest.xml
Removed Paths:
-------------
pkg/trunk/3rdparty/sdl/SDL-1.2.13.tar.gz
pkg/trunk/3rdparty/sdl/manifest.xml
pkg/trunk/3rdparty/sdl/rosbuild
pkg/trunk/sdl/
Copied: pkg/trunk/3rdparty/sdl (from rev 158, pkg/trunk/sdl)
Copied: pkg/trunk/3rdparty/sdl/Makefile (from rev 159, pkg/trunk/sdl/Makefile)
===================================================================
--- pkg/trunk/3rdparty/sdl/Makefile (rev 0)
+++ pkg/trunk/3rdparty/sdl/Makefile 2008-04-22 23:58:24 UTC (rev 160)
@@ -0,0 +1,16 @@
+all: SDL
+
+SDL-1.2.13:
+ tar xzf SDL-1.2.13.tar.gz
+
+SDL: SDL-1.2.13
+ @if [ ! -d /usr/include/X11 ]; then echo "you don't appear to have X. On Ubuntu, this is fixed with 'sudo apt-get install xorg-dev'"; false; fi
+ @if [ ! -f /usr/include/GL/gl.h ]; then echo "you don't appear to have OpenGL. On Ubuntu, this is fixed with 'sudo apt-get install libgl1-mesa-dev'"; false; fi
+ @if [ ! -f /usr/include/GL/glu.h ]; then echo "you don't appear to have the OpenGL GLU library. On Ubuntu, this can be fixed with 'sudo apt-get install libglu1-mesa-dev'"; false; fi
+ cd SDL-1.2.13 && ./configure --prefix=$(PWD)/SDL
+ cd SDL-1.2.13 && make && make install
+
+clean:
+ -rm -rf SDL-1.2.13 SDL
+
+.PHONY : clean
Deleted: pkg/trunk/3rdparty/sdl/SDL-1.2.13.tar.gz
===================================================================
(Binary files differ)
Copied: pkg/trunk/3rdparty/sdl/SDL-1.2.13.tar.gz (from rev 159, pkg/trunk/sdl/SDL-1.2.13.tar.gz)
===================================================================
(Binary files differ)
Deleted: pkg/trunk/3rdparty/sdl/manifest.xml
===================================================================
--- pkg/trunk/sdl/manifest.xml 2008-04-22 23:35:36 UTC (rev 158)
+++ pkg/trunk/3rdparty/sdl/manifest.xml 2008-04-22 23:58:24 UTC (rev 160)
@@ -1,14 +0,0 @@
-<package>
-<description brief="The Simple DirectMedia Layer">
-
-This package contains the Simple DirectMedia Layer (SDL). This package does not
-modify SDL in any way; it simply provides a convenient way to download and
-compile the library's shared object in a way that can be managed by the ROS
-dependency system.
-
-</description>
-<author>Sam Lantinga, with contributions from many others. See web page for a full credits llist.</author>
-<license>LGPL</license>
-<url>http://www.libsdl.org</url>
-</package>
-
Copied: pkg/trunk/3rdparty/sdl/manifest.xml (from rev 159, pkg/trunk/sdl/manifest.xml)
===================================================================
--- pkg/trunk/3rdparty/sdl/manifest.xml (rev 0)
+++ pkg/trunk/3rdparty/sdl/manifest.xml 2008-04-22 23:58:24 UTC (rev 160)
@@ -0,0 +1,17 @@
+<package>
+<description brief="The Simple DirectMedia Layer">
+
+This package contains the Simple DirectMedia Layer (SDL). This package does not
+modify SDL in any way; it simply provides a convenient way to download and
+compile the library's shared object in a way that can be managed by the ROS
+dependency system.
+
+</description>
+<author>Sam Lantinga, with contributions from many others. See web page for a full credits llist.</author>
+<license>LGPL</license>
+<url>http://www.libsdl.org</url>
+<export>
+ <cpp lflags="-Xlinker -rpath ${prefix}/SDL/lib -L${prefix}/SDL/lib -lSDL" cflags="-I${prefix}/SDL/include"/>
+</export>
+</package>
+
Deleted: pkg/trunk/3rdparty/sdl/rosbuild
===================================================================
--- pkg/trunk/sdl/rosbuild 2008-04-22 23:35:36 UTC (rev 158)
+++ pkg/trunk/3rdparty/sdl/rosbuild 2008-04-22 23:58:24 UTC (rev 160)
@@ -1,44 +0,0 @@
-#!/usr/bin/env ruby
-require 'fileutils.rb'
-
-pkg_path = File.expand_path($0).split('/')
-pkg_path = pkg_path[0,pkg_path.length-1].join('/')
-puts "package path: [#{pkg_path}]"
-if pkg_path.length < 1
- puts "woah! package path looks scary. something isn't right. bailing..."
- exit
-end
-
-Dir.chdir(pkg_path)
-# TODO make sure we got there
-
-if ARGV.length == 0 || ARGV[0] == 'update'
- puts "extracting SDL ============================"
- system("tar xzvf SDL-1.2.13.tar.gz")
- Dir.mkdir 'bin' if !File.exists? 'bin'
- Dir.mkdir 'lib' if !File.exists? 'lib'
- Dir.mkdir 'man' if !File.exists? 'man'
- Dir.mkdir 'man/man1' if !File.exists? 'man/man1'
- puts "configuring libsdl ============================"
- Dir.chdir "#{pkg_path}/SDL-1.2.13"
- system("./configure --prefix=${PWD}/..")
-# TODO check for blowups after configure
- puts "making libsdl ================================="
- system("make")
- puts "moving files around ============================"
- system("make install")
-# TODO check for make errors
- puts "done! hooray! =================================="
-elsif ARGV[0] == 'clean'
- Dir.chdir "#{pkg_path}"
- system("rm -rf bin")
- system("rm -rf include")
- system("rm -rf lib")
- system("rm -rf man")
- system("rm -rf share")
- system("rm -rf SDL-1.2.13")
- puts "done!"
-else
- puts "unknown parameter: #{ARGV[0]}"
-end
-
Modified: pkg/trunk/axis_cam/nodes/test_axis_cam
===================================================================
--- pkg/trunk/axis_cam/nodes/test_axis_cam 2008-04-22 23:57:06 UTC (rev 159)
+++ pkg/trunk/axis_cam/nodes/test_axis_cam 2008-04-22 23:58:24 UTC (rev 160)
@@ -2,8 +2,8 @@
require "#{`#{ENV['ROS_ROOT']}/rospack latest yamlgraph`}/lib/yamlgraph/ygl.rb"
g = YAMLGraph.new
g.param 'axis_cam.host', '192.168.1.90'
-g.node 'axis_cam/axis_cam', {'launch'=>'xterm'}
-g.node 'image_viewer/image_viewer', {'launch'=>'xterm'}
+g.node 'axis_cam/axis_cam', {'launch'=>'valgrind'}
+g.node 'image_viewer/image_viewer', {'launch'=>'valgrind'}
#g.node 'vacuum/vacuum', {'launch' => 'valgrind'}
g.flow 'axis_cam:image', 'image_viewer:image'
#g.flow 'axis_cam:image', 'vacuum:hose'
Modified: pkg/trunk/cloud_viewer/src/standalone/Makefile
===================================================================
--- pkg/trunk/cloud_viewer/src/standalone/Makefile 2008-04-22 23:57:06 UTC (rev 159)
+++ pkg/trunk/cloud_viewer/src/standalone/Makefile 2008-04-22 23:58:24 UTC (rev 160)
@@ -1,6 +1,7 @@
SRC = cloud.cpp
OUT = cloud
PKG = cloud_viewer
-CFLAGS = -I$(shell $(ROS_ROOT)/rospack find sdl)/include -I../../include
-LFLAGS = -L$(shell $(ROS_ROOT)/rospack find sdl)/lib -lSDL -L../../lib -lcloud_viewer -lGL -lGLU
-include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/only_rules.mk
+#CFLAGS = -I$(shell $(ROS_ROOT)/rospack find sdl)/include -I../../include
+#LFLAGS = -L$(shell $(ROS_ROOT)/rospack find sdl)/lib -lSDL -L../../lib -lcloud_viewer -lGL -lGLU
+#include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/only_rules.mk
+include $(shell rospack find mk)/node.mk
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2008-04-23 16:09:53
|
Revision: 164
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=164&view=rev
Author: jleibs
Date: 2008-04-23 09:09:53 -0700 (Wed, 23 Apr 2008)
Log Message:
-----------
Rolling back morgans changes that are now located in the rosbus branch.
Modified Paths:
--------------
pkg/trunk/axis_cam/nodes/test_axis_cam
pkg/trunk/cloud_viewer/src/standalone/Makefile
Added Paths:
-----------
pkg/trunk/sdl/
pkg/trunk/sdl/SDL-1.2.13.tar.gz
pkg/trunk/sdl/manifest.xml
pkg/trunk/sdl/rosbuild
Removed Paths:
-------------
pkg/trunk/3rdparty/
pkg/trunk/sdl/SDL-1.2.13.tar.gz
pkg/trunk/sdl/manifest.xml
pkg/trunk/sdl/rosbuild
Modified: pkg/trunk/axis_cam/nodes/test_axis_cam
===================================================================
--- pkg/trunk/axis_cam/nodes/test_axis_cam 2008-04-23 15:44:47 UTC (rev 163)
+++ pkg/trunk/axis_cam/nodes/test_axis_cam 2008-04-23 16:09:53 UTC (rev 164)
@@ -2,8 +2,8 @@
require "#{`#{ENV['ROS_ROOT']}/rospack latest yamlgraph`}/lib/yamlgraph/ygl.rb"
g = YAMLGraph.new
g.param 'axis_cam.host', '192.168.1.90'
-g.node 'axis_cam/axis_cam', {'launch'=>'valgrind'}
-g.node 'image_viewer/image_viewer', {'launch'=>'valgrind'}
+g.node 'axis_cam/axis_cam', {'launch'=>'xterm'}
+g.node 'image_viewer/image_viewer', {'launch'=>'xterm'}
#g.node 'vacuum/vacuum', {'launch' => 'valgrind'}
g.flow 'axis_cam:image', 'image_viewer:image'
#g.flow 'axis_cam:image', 'vacuum:hose'
Modified: pkg/trunk/cloud_viewer/src/standalone/Makefile
===================================================================
--- pkg/trunk/cloud_viewer/src/standalone/Makefile 2008-04-23 15:44:47 UTC (rev 163)
+++ pkg/trunk/cloud_viewer/src/standalone/Makefile 2008-04-23 16:09:53 UTC (rev 164)
@@ -1,7 +1,6 @@
SRC = cloud.cpp
OUT = cloud
PKG = cloud_viewer
-#CFLAGS = -I$(shell $(ROS_ROOT)/rospack find sdl)/include -I../../include
-#LFLAGS = -L$(shell $(ROS_ROOT)/rospack find sdl)/lib -lSDL -L../../lib -lcloud_viewer -lGL -lGLU
-#include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/only_rules.mk
-include $(shell rospack find mk)/node.mk
+CFLAGS = -I$(shell $(ROS_ROOT)/rospack find sdl)/include -I../../include
+LFLAGS = -L$(shell $(ROS_ROOT)/rospack find sdl)/lib -lSDL -L../../lib -lcloud_viewer -lGL -lGLU
+include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/only_rules.mk
Copied: pkg/trunk/sdl (from rev 158, pkg/trunk/sdl)
Property changes on: pkg/trunk/sdl
___________________________________________________________________
Name: svn:ignore
+ share
SDL-1.2.13
include
lib
bin
man
Deleted: pkg/trunk/sdl/SDL-1.2.13.tar.gz
===================================================================
(Binary files differ)
Copied: pkg/trunk/sdl/SDL-1.2.13.tar.gz (from rev 158, pkg/trunk/sdl/SDL-1.2.13.tar.gz)
===================================================================
(Binary files differ)
Deleted: pkg/trunk/sdl/manifest.xml
===================================================================
--- pkg/trunk/sdl/manifest.xml 2008-04-22 23:35:36 UTC (rev 158)
+++ pkg/trunk/sdl/manifest.xml 2008-04-23 16:09:53 UTC (rev 164)
@@ -1,14 +0,0 @@
-<package>
-<description brief="The Simple DirectMedia Layer">
-
-This package contains the Simple DirectMedia Layer (SDL). This package does not
-modify SDL in any way; it simply provides a convenient way to download and
-compile the library's shared object in a way that can be managed by the ROS
-dependency system.
-
-</description>
-<author>Sam Lantinga, with contributions from many others. See web page for a full credits llist.</author>
-<license>LGPL</license>
-<url>http://www.libsdl.org</url>
-</package>
-
Copied: pkg/trunk/sdl/manifest.xml (from rev 158, pkg/trunk/sdl/manifest.xml)
===================================================================
--- pkg/trunk/sdl/manifest.xml (rev 0)
+++ pkg/trunk/sdl/manifest.xml 2008-04-23 16:09:53 UTC (rev 164)
@@ -0,0 +1,14 @@
+<package>
+<description brief="The Simple DirectMedia Layer">
+
+This package contains the Simple DirectMedia Layer (SDL). This package does not
+modify SDL in any way; it simply provides a convenient way to download and
+compile the library's shared object in a way that can be managed by the ROS
+dependency system.
+
+</description>
+<author>Sam Lantinga, with contributions from many others. See web page for a full credits llist.</author>
+<license>LGPL</license>
+<url>http://www.libsdl.org</url>
+</package>
+
Deleted: pkg/trunk/sdl/rosbuild
===================================================================
--- pkg/trunk/sdl/rosbuild 2008-04-22 23:35:36 UTC (rev 158)
+++ pkg/trunk/sdl/rosbuild 2008-04-23 16:09:53 UTC (rev 164)
@@ -1,44 +0,0 @@
-#!/usr/bin/env ruby
-require 'fileutils.rb'
-
-pkg_path = File.expand_path($0).split('/')
-pkg_path = pkg_path[0,pkg_path.length-1].join('/')
-puts "package path: [#{pkg_path}]"
-if pkg_path.length < 1
- puts "woah! package path looks scary. something isn't right. bailing..."
- exit
-end
-
-Dir.chdir(pkg_path)
-# TODO make sure we got there
-
-if ARGV.length == 0 || ARGV[0] == 'update'
- puts "extracting SDL ============================"
- system("tar xzvf SDL-1.2.13.tar.gz")
- Dir.mkdir 'bin' if !File.exists? 'bin'
- Dir.mkdir 'lib' if !File.exists? 'lib'
- Dir.mkdir 'man' if !File.exists? 'man'
- Dir.mkdir 'man/man1' if !File.exists? 'man/man1'
- puts "configuring libsdl ============================"
- Dir.chdir "#{pkg_path}/SDL-1.2.13"
- system("./configure --prefix=${PWD}/..")
-# TODO check for blowups after configure
- puts "making libsdl ================================="
- system("make")
- puts "moving files around ============================"
- system("make install")
-# TODO check for make errors
- puts "done! hooray! =================================="
-elsif ARGV[0] == 'clean'
- Dir.chdir "#{pkg_path}"
- system("rm -rf bin")
- system("rm -rf include")
- system("rm -rf lib")
- system("rm -rf man")
- system("rm -rf share")
- system("rm -rf SDL-1.2.13")
- puts "done!"
-else
- puts "unknown parameter: #{ARGV[0]}"
-end
-
Copied: pkg/trunk/sdl/rosbuild (from rev 158, pkg/trunk/sdl/rosbuild)
===================================================================
--- pkg/trunk/sdl/rosbuild (rev 0)
+++ pkg/trunk/sdl/rosbuild 2008-04-23 16:09:53 UTC (rev 164)
@@ -0,0 +1,44 @@
+#!/usr/bin/env ruby
+require 'fileutils.rb'
+
+pkg_path = File.expand_path($0).split('/')
+pkg_path = pkg_path[0,pkg_path.length-1].join('/')
+puts "package path: [#{pkg_path}]"
+if pkg_path.length < 1
+ puts "woah! package path looks scary. something isn't right. bailing..."
+ exit
+end
+
+Dir.chdir(pkg_path)
+# TODO make sure we got there
+
+if ARGV.length == 0 || ARGV[0] == 'update'
+ puts "extracting SDL ============================"
+ system("tar xzvf SDL-1.2.13.tar.gz")
+ Dir.mkdir 'bin' if !File.exists? 'bin'
+ Dir.mkdir 'lib' if !File.exists? 'lib'
+ Dir.mkdir 'man' if !File.exists? 'man'
+ Dir.mkdir 'man/man1' if !File.exists? 'man/man1'
+ puts "configuring libsdl ============================"
+ Dir.chdir "#{pkg_path}/SDL-1.2.13"
+ system("./configure --prefix=${PWD}/..")
+# TODO check for blowups after configure
+ puts "making libsdl ================================="
+ system("make")
+ puts "moving files around ============================"
+ system("make install")
+# TODO check for make errors
+ puts "done! hooray! =================================="
+elsif ARGV[0] == 'clean'
+ Dir.chdir "#{pkg_path}"
+ system("rm -rf bin")
+ system("rm -rf include")
+ system("rm -rf lib")
+ system("rm -rf man")
+ system("rm -rf share")
+ system("rm -rf SDL-1.2.13")
+ puts "done!"
+else
+ puts "unknown parameter: #{ARGV[0]}"
+end
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2008-04-24 02:01:24
|
Revision: 176
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=176&view=rev
Author: jleibs
Date: 2008-04-23 19:01:29 -0700 (Wed, 23 Apr 2008)
Log Message:
-----------
Checking in library for building kdtrees.
Added Paths:
-----------
pkg/trunk/kdtree/
pkg/trunk/kdtree/Makefile
pkg/trunk/kdtree/include/
pkg/trunk/kdtree/include/kdtree/
pkg/trunk/kdtree/kdtree2.tar.gz
pkg/trunk/kdtree/lib/
pkg/trunk/kdtree/manifest.xml
pkg/trunk/kdtree/rosbuild
pkg/trunk/kdtree/test/
pkg/trunk/kdtree/test/Makefile
pkg/trunk/kdtree/test/test.cpp
Added: pkg/trunk/kdtree/Makefile
===================================================================
--- pkg/trunk/kdtree/Makefile (rev 0)
+++ pkg/trunk/kdtree/Makefile 2008-04-24 02:01:29 UTC (rev 176)
@@ -0,0 +1,4 @@
+SRC = kdtree2.31/src-c++/kdtree2.cpp
+OUT = lib/libkdtree.a
+PKG = kdtree
+include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/lib.mk
Added: pkg/trunk/kdtree/kdtree2.tar.gz
===================================================================
(Binary files differ)
Property changes on: pkg/trunk/kdtree/kdtree2.tar.gz
___________________________________________________________________
Name: svn:mime-type
+ application/octet-stream
Added: pkg/trunk/kdtree/manifest.xml
===================================================================
--- pkg/trunk/kdtree/manifest.xml (rev 0)
+++ pkg/trunk/kdtree/manifest.xml 2008-04-24 02:01:29 UTC (rev 176)
@@ -0,0 +1,9 @@
+<package>
+<description brief="KDTree library">
+A Wrapper for the KDTREE2 library.
+</description>
+<author>Matthew B. Kennel</author>
+<license>Academic Free License 1.1</license>
+<url>http://arxiv.org/abs/physics/0408067</url>
+</package>
+
Added: pkg/trunk/kdtree/rosbuild
===================================================================
--- pkg/trunk/kdtree/rosbuild (rev 0)
+++ pkg/trunk/kdtree/rosbuild 2008-04-24 02:01:29 UTC (rev 176)
@@ -0,0 +1,36 @@
+#!/usr/bin/env ruby
+require 'fileutils.rb'
+
+pkg_path = File.expand_path($0).split('/')
+pkg_path = pkg_path[0,pkg_path.length-1].join('/')
+puts "package path: [#{pkg_path}]"
+if pkg_path.length < 1
+ puts "woah! package path looks scary. something isn't right. bailing..."
+ exit
+end
+
+Dir.chdir(pkg_path)
+# TODO make sure we got there
+
+if ARGV.length == 0 || ARGV[0] == 'update'
+ puts "extracting KDTree ============================"
+ system("tar xzvf kdtree2.tar.gz")
+ system("cp kdtree2.31/src-c++/kdtree2.hpp include/kdtree/")
+ puts "making kdtree2 ================================="
+ system("make")
+ puts "building test ================================="
+ Dir.chdir "#{pkg_path}/test"
+ system("make")
+ puts "done! hooray! =================================="
+elsif ARGV[0] == 'clean'
+ Dir.chdir "#{pkg_path}"
+ system("make clean")
+ system("rm -rf kdtree2.31")
+ system("rm include/kdtree/kdtree2.hpp")
+ Dir.chdir "#{pkg_path}/test"
+ system("make clean")
+ puts "done!"
+else
+ puts "unknown parameter: #{ARGV[0]}"
+end
+
Property changes on: pkg/trunk/kdtree/rosbuild
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/kdtree/test/Makefile
===================================================================
--- pkg/trunk/kdtree/test/Makefile (rev 0)
+++ pkg/trunk/kdtree/test/Makefile 2008-04-24 02:01:29 UTC (rev 176)
@@ -0,0 +1,4 @@
+SRC = test.cpp
+OUT = test
+PKG = kdtree
+include $(shell $(ROS_ROOT)/rospack find roscpp)/make_include/node.mk
Added: pkg/trunk/kdtree/test/test.cpp
===================================================================
--- pkg/trunk/kdtree/test/test.cpp (rev 0)
+++ pkg/trunk/kdtree/test/test.cpp 2008-04-24 02:01:29 UTC (rev 176)
@@ -0,0 +1,78 @@
+#include "kdtree/kdtree2.hpp"
+
+#include <boost/multi_array.hpp>
+#include <boost/random.hpp>
+#include <sys/time.h>
+
+using namespace boost;
+
+ double timeval_diff (struct timeval x,
+ struct timeval y) {
+ double dsec = x.tv_sec - y.tv_sec;
+ double dusec = x.tv_usec - y.tv_usec;
+ return dsec + dusec/1000000.0;
+ }
+
+static minstd_rand generator(42u);
+static uniform_real<> uni_dist(0,1);
+variate_generator<minstd_rand&,uniform_real<> > uni(generator,uni_dist);
+
+float random_variate() {
+ // between [0,1)
+ return(uni());
+}
+
+//
+// define, for convenience a 2d array of floats.
+//
+typedef multi_array<float,2> array2dfloat;
+
+int main() {
+ array2dfloat realdata;
+
+ kdtree2* tree;
+
+ int N = 1000000;
+ int dim = 3;
+
+ struct timeval t0, t1;
+
+ realdata.resize(extents[N][dim]);
+
+ for (int i=0; i<N; i++) {
+ for (int j=0; j<dim; j++)
+ realdata[i][j] = random_variate();
+ }
+
+ kdtree2_result_vector result, resultbrute;
+
+ cout << "Building tree... ";
+
+ gettimeofday(&t0, NULL);
+
+ tree = new kdtree2(realdata,true);
+ tree->sort_results = false;
+
+ gettimeofday(&t1, NULL);
+ cout << timeval_diff(t1, t0) << endl;
+
+ int nn = 1;
+
+ // tree->n_nearest_around_point(150000,1,nn,result);
+
+ cout << "Finding nearest... ";
+
+ gettimeofday(&t0, NULL);
+ for (int k = 0; k < N;k++) {
+ tree->n_nearest_around_point(k,1,nn,result);
+ }
+ gettimeofday(&t1, NULL);
+ cout << timeval_diff(t1, t0) << endl;
+
+ /*
+ for (int k=0; k<nn; k++) {
+ cout << "Result " << k << ", " << result[k].dis << ", " << result[k].idx << endl;
+ }
+ */
+}
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mm...@us...> - 2008-04-28 21:11:13
|
Revision: 212
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=212&view=rev
Author: mmwise
Date: 2008-04-28 14:11:18 -0700 (Mon, 28 Apr 2008)
Log Message:
-----------
adding the controller dir and changed the IP address on the etherdrive2
test file
Modified Paths:
--------------
pkg/trunk/etherdrive/test/test_etherdrive2/test_etherdrive2.cpp
Added Paths:
-----------
pkg/trunk/controllers/
Modified: pkg/trunk/etherdrive/test/test_etherdrive2/test_etherdrive2.cpp
===================================================================
--- pkg/trunk/etherdrive/test/test_etherdrive2/test_etherdrive2.cpp 2008-04-28 18:27:32 UTC (rev 211)
+++ pkg/trunk/etherdrive/test/test_etherdrive2/test_etherdrive2.cpp 2008-04-28 21:11:18 UTC (rev 212)
@@ -41,7 +41,7 @@
EtherDrive e;
- if (!e.init("10.0.0.151")) {
+ if (!e.init("192.168.0.100")) {
cout << "Could not initialize etherdrive." << endl;
return -1;
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mm...@us...> - 2008-04-30 18:50:37
|
Revision: 246
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=246&view=rev
Author: mmwise
Date: 2008-04-30 11:50:41 -0700 (Wed, 30 Apr 2008)
Log Message:
-----------
added begining auto_calibration
Modified Paths:
--------------
pkg/trunk/controllers/src/Pid.cpp
pkg/trunk/exploreGraph/nodes/renderGraph
Added Paths:
-----------
pkg/trunk/auto_calibration/
pkg/trunk/auto_calibration/manifest.xml
Added: pkg/trunk/auto_calibration/manifest.xml
===================================================================
--- pkg/trunk/auto_calibration/manifest.xml (rev 0)
+++ pkg/trunk/auto_calibration/manifest.xml 2008-04-30 18:50:41 UTC (rev 246)
@@ -0,0 +1,11 @@
+<package>
+<description brief='Auto Calibration Library'>
+
+Library for doing transformations.
+
+</description>
+<author>Melonee Wise</author>
+<license>BSD</license>
+<url>http://pr.willowgarage.com</url>
+<repository>http://pr.willowgarage.com/repos</repository>
+</package>
Modified: pkg/trunk/controllers/src/Pid.cpp
===================================================================
--- pkg/trunk/controllers/src/Pid.cpp 2008-04-30 02:26:07 UTC (rev 245)
+++ pkg/trunk/controllers/src/Pid.cpp 2008-04-30 18:50:41 UTC (rev 246)
@@ -1,6 +1,6 @@
#include "Pid.h"
#include<iostream>
- #include "timer.h"
+#include "timer.h"
using namespace std;
Modified: pkg/trunk/exploreGraph/nodes/renderGraph
===================================================================
--- pkg/trunk/exploreGraph/nodes/renderGraph 2008-04-30 02:26:07 UTC (rev 245)
+++ pkg/trunk/exploreGraph/nodes/renderGraph 2008-04-30 18:50:41 UTC (rev 246)
@@ -50,6 +50,6 @@
# so when the packaged version gets upgraded we can remove this
# todo clean this out when it's upgraded
# https://bugs.launchpad.net/ubuntu/+source/graphviz/+bug/208072
-launchEnv['LD_PRELOAD'] = '/usr/lib/libgvc.so.3'
+#launchEnv['LD_PRELOAD'] = '/usr/lib/libgvc.so.3'
os.execvpe(launchCommand, launchArgs, launchEnv)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2008-05-01 16:19:56
|
Revision: 277
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=277&view=rev
Author: jleibs
Date: 2008-05-01 09:19:57 -0700 (Thu, 01 May 2008)
Log Message:
-----------
Tilting laser in ported and almost working.
Modified Paths:
--------------
pkg/trunk/drivers/laser/hokuyourg_player/Makefile
pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc
pkg/trunk/drivers/motor/etherdrive/src/etherdrive_node/etherdrive_node.cpp
pkg/trunk/drivers/robot/pr2/tilting_laser/src/tilting_laser/tilting_laser.cpp
Added Paths:
-----------
pkg/trunk/drivers/robot/pr2/
pkg/trunk/drivers/robot/pr2/tilting_laser/
pkg/trunk/drivers/robot/pr2/tilting_laser/launch_tl
pkg/trunk/drivers/robot/pr2/tilting_laser/params.xml
Removed Paths:
-------------
pkg/trunk/unported/tilting_laser/
Modified: pkg/trunk/drivers/laser/hokuyourg_player/Makefile
===================================================================
--- pkg/trunk/drivers/laser/hokuyourg_player/Makefile 2008-05-01 16:19:54 UTC (rev 276)
+++ pkg/trunk/drivers/laser/hokuyourg_player/Makefile 2008-05-01 16:19:57 UTC (rev 277)
@@ -4,7 +4,8 @@
#CFLAGS = -g -Wall -Werror `pkg-config --cflags-only-I playercore` `rospack export/cpp/cflags $(PKG)`
#LFLAGS = `pkg-config --libs-only-L playercore` -lurglaser_standalone `rospack export/cpp/lflags $(PKG)`
-CFLAGS = -g -Wall -Werror `rospack export/cpp/cflags $(PKG)`
+#CFLAGS = -g -Wall -Werror `rospack export/cpp/cflags $(PKG)`
+CFLAGS = -g -Wall `rospack export/cpp/cflags $(PKG)`
LFLAGS = `rospack export/cpp/lflags $(PKG)` -lurglaser_standalone
hokuyourg_player: hokuyourg_player.cc
Modified: pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc
===================================================================
--- pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc 2008-05-01 16:19:54 UTC (rev 276)
+++ pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc 2008-05-01 16:19:57 UTC (rev 277)
@@ -22,7 +22,7 @@
HokuyoNode() : ros::node("urglaser")
{
- advertise("scan", scan);
+ advertise<MsgLaserScan>("scan");
// TODO: add min/max angle support
/*
@@ -89,7 +89,7 @@
scan.angle_max = cfg.max_angle;
scan.angle_increment = cfg.resolution;
scan.range_max = cfg.max_range;
- scan.id = scanid++;
+ scan.header.seq = scanid++;
scan.set_ranges_size(numreadings);
scan.set_intensities_size(numreadings);
Modified: pkg/trunk/drivers/motor/etherdrive/src/etherdrive_node/etherdrive_node.cpp
===================================================================
--- pkg/trunk/drivers/motor/etherdrive/src/etherdrive_node/etherdrive_node.cpp 2008-05-01 16:19:54 UTC (rev 276)
+++ pkg/trunk/drivers/motor/etherdrive/src/etherdrive_node/etherdrive_node.cpp 2008-05-01 16:19:57 UTC (rev 277)
@@ -51,7 +51,7 @@
for (int i = 0;i < 6;i++) {
ostringstream oss;
oss << "mot" << i;
- advertise(oss.str().c_str(), mot[i]);
+ advertise<MsgActuator>(oss.str().c_str());
oss << "_cmd";
subscribe(oss.str().c_str(), mot_cmd[i], &EtherDrive_Node::mot_callback);
Copied: pkg/trunk/drivers/robot/pr2/tilting_laser (from rev 274, pkg/trunk/unported/tilting_laser)
Added: pkg/trunk/drivers/robot/pr2/tilting_laser/launch_tl
===================================================================
--- pkg/trunk/drivers/robot/pr2/tilting_laser/launch_tl (rev 0)
+++ pkg/trunk/drivers/robot/pr2/tilting_laser/launch_tl 2008-05-01 16:19:57 UTC (rev 277)
@@ -0,0 +1,6 @@
+#!/bin/bash
+export ROS_NAMESPACE=$ROS_NAMESPACE/TL
+`rospack find xmlparam`/xmlparam `rospack find tilting_laser`/params.xml
+xterm -e `rospack find hokuyourg_player`/hokuyourg_player&
+xterm -e `rospack find etherdrive`/bin/etherdrive &
+xterm -e `rospack find tilting_laser`/bin/tilting_laser mot:=mot2 mot_cmd:=mot2_cmd&
Property changes on: pkg/trunk/drivers/robot/pr2/tilting_laser/launch_tl
___________________________________________________________________
Name: svn:executable
+ *
Added: pkg/trunk/drivers/robot/pr2/tilting_laser/params.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/tilting_laser/params.xml (rev 0)
+++ pkg/trunk/drivers/robot/pr2/tilting_laser/params.xml 2008-05-01 16:19:57 UTC (rev 277)
@@ -0,0 +1,5 @@
+<params>
+ <double name=".period">5.0</double>
+ <double name=".min_ang">-1.3</double>
+ <double name=".max_ang">0.6</double>
+</params>
Modified: pkg/trunk/drivers/robot/pr2/tilting_laser/src/tilting_laser/tilting_laser.cpp
===================================================================
--- pkg/trunk/unported/tilting_laser/src/tilting_laser/tilting_laser.cpp 2008-05-01 03:06:04 UTC (rev 274)
+++ pkg/trunk/drivers/robot/pr2/tilting_laser/src/tilting_laser/tilting_laser.cpp 2008-05-01 16:19:57 UTC (rev 277)
@@ -68,12 +68,12 @@
Tilting_Laser() : ros::node("tilting_laser"), next_shutter(0.0)
{
- advertise("cloud", cloud);
- advertise("shutter", shutter);
- advertise("mot2_cmd", cmd);
+ advertise<MsgPointCloudFloat32>("cloud");
+ advertise<MsgEmpty>("shutter");
+ advertise<MsgActuator>("mot_cmd");
subscribe("scan", scans, &Tilting_Laser::scans_callback);
- subscribe("mot2", encoder, &Tilting_Laser::encoder_callback);
+ subscribe("mot", encoder, &Tilting_Laser::encoder_callback);
if (!get_param(".period", period))
period = 5.0;
@@ -156,7 +156,7 @@
time);
motor_control(); // Control on encoder reads sounds reasonable
- // printf("I got some encoder values: %g!\n", encoder.val);
+ printf("I got some encoder values: %g!\n", encoder.val);
}
void motor_control() {
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-05-02 16:43:25
|
Revision: 290
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=290&view=rev
Author: gerkey
Date: 2008-05-02 09:43:31 -0700 (Fri, 02 May 2008)
Log Message:
-----------
porting nodes
Modified Paths:
--------------
pkg/trunk/3rdparty/player/manifest.xml
pkg/trunk/unported/erratic_player/erratic_player.cc
pkg/trunk/unported/gmapping/playerwrapper/playergfswrapper.cpp
Modified: pkg/trunk/3rdparty/player/manifest.xml
===================================================================
--- pkg/trunk/3rdparty/player/manifest.xml 2008-05-02 16:43:03 UTC (rev 289)
+++ pkg/trunk/3rdparty/player/manifest.xml 2008-05-02 16:43:31 UTC (rev 290)
@@ -12,7 +12,7 @@
<license>LGPL</license>
<url>http://playerstage.sf.net</url>
<export>
- <cpp lflags="-Xlinker -rpath ${prefix}/player/lib -L${prefix}/player/lib -lplayercore -lplayerxdr -lplayerutils -lplayererror" cflags="-I${prefix}/player/include/player-2.2"/>
+ <cpp lflags="-Xlinker -rpath ${prefix}/player/lib -L${prefix}/player/lib -lplayerdrivers -lplayercore -lplayerxdr -lplayerutils -lplayererror" cflags="-I${prefix}/player/include/player-2.2"/>
</export>
</package>
Modified: pkg/trunk/unported/erratic_player/erratic_player.cc
===================================================================
--- pkg/trunk/unported/erratic_player/erratic_player.cc 2008-05-02 16:43:03 UTC (rev 289)
+++ pkg/trunk/unported/erratic_player/erratic_player.cc 2008-05-02 16:43:31 UTC (rev 290)
@@ -151,8 +151,10 @@
};
int
-main(void)
+main(int argc, char** argv)
{
+ ros::init(argc, argv);
+
ErraticNode en;
Message* msg;
@@ -192,7 +194,7 @@
en.odom.stall = pdata->stall;
// Publish the new data
- publish("odom", odom);
+ en.publish("odom", en.odom);
printf("Published new odom: (%.3f,%.3f,%.3f)\n",
en.odom.px, en.odom.py, en.odom.pyaw);
Modified: pkg/trunk/unported/gmapping/playerwrapper/playergfswrapper.cpp
===================================================================
--- pkg/trunk/unported/gmapping/playerwrapper/playergfswrapper.cpp 2008-05-02 16:43:03 UTC (rev 289)
+++ pkg/trunk/unported/gmapping/playerwrapper/playergfswrapper.cpp 2008-05-02 16:43:31 UTC (rev 290)
@@ -22,6 +22,8 @@
*
*****************************************************************/
+#include <float.h>
+
#include <gui/qparticleviewer.h>
#include <gui/qgraphpainter.h>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mm...@us...> - 2008-05-05 22:10:53
|
Revision: 308
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=308&view=rev
Author: mmwise
Date: 2008-05-05 15:10:58 -0700 (Mon, 05 May 2008)
Log Message:
-----------
adding documentation directory
Added Paths:
-----------
pkg/trunk/documentation/
pkg/trunk/documentation/Makefile
pkg/trunk/documentation/doxy
Added: pkg/trunk/documentation/Makefile
===================================================================
--- pkg/trunk/documentation/Makefile (rev 0)
+++ pkg/trunk/documentation/Makefile 2008-05-05 22:10:58 UTC (rev 308)
@@ -0,0 +1,12 @@
+all: docs
+docs:
+ doxygen doxy
+
+upload: docs
+ scp -P 2222 -r html /var/www/pr.willowgarage.com/html/pr-docs/personalrobots
+
+upload-local: docs
+ cp -R html /var/www/pr.willowgarage.com/html/pr-docs/personalrobots
+
+clean:
+ rm -rf html latex
Added: pkg/trunk/documentation/doxy
===================================================================
--- pkg/trunk/documentation/doxy (rev 0)
+++ pkg/trunk/documentation/doxy 2008-05-05 22:10:58 UTC (rev 308)
@@ -0,0 +1,225 @@
+# Doxyfile 1.5.1
+
+#---------------------------------------------------------------------------
+# Project related configuration options
+#---------------------------------------------------------------------------
+PROJECT_NAME = personalrobots
+PROJECT_NUMBER =
+OUTPUT_DIRECTORY =
+CREATE_SUBDIRS = NO
+OUTPUT_LANGUAGE = English
+USE_WINDOWS_ENCODING = NO
+BRIEF_MEMBER_DESC = YES
+REPEAT_BRIEF = YES
+ABBREVIATE_BRIEF =
+ALWAYS_DETAILED_SEC = NO
+INLINE_INHERITED_MEMB = NO
+FULL_PATH_NAMES = YES
+STRIP_FROM_PATH =
+STRIP_FROM_INC_PATH =
+SHORT_NAMES = NO
+JAVADOC_AUTOBRIEF = NO
+MULTILINE_CPP_IS_BRIEF = NO
+DETAILS_AT_TOP = NO
+INHERIT_DOCS = YES
+SEPARATE_MEMBER_PAGES = NO
+TAB_SIZE = 8
+ALIASES =
+OPTIMIZE_OUTPUT_FOR_C = NO
+OPTIMIZE_OUTPUT_JAVA = NO
+BUILTIN_STL_SUPPORT = NO
+DISTRIBUTE_GROUP_DOC = NO
+SUBGROUPING = YES
+#---------------------------------------------------------------------------
+# Build related configuration options
+#---------------------------------------------------------------------------
+EXTRACT_ALL = YES
+EXTRACT_PRIVATE = YES
+EXTRACT_STATIC = YES
+EXTRACT_LOCAL_CLASSES = YES
+EXTRACT_LOCAL_METHODS = NO
+HIDE_UNDOC_MEMBERS = NO
+HIDE_UNDOC_CLASSES = NO
+HIDE_FRIEND_COMPOUNDS = NO
+HIDE_IN_BODY_DOCS = NO
+INTERNAL_DOCS = NO
+CASE_SENSE_NAMES = YES
+HIDE_SCOPE_NAMES = NO
+SHOW_INCLUDE_FILES = YES
+INLINE_INFO = YES
+SORT_MEMBER_DOCS = YES
+SORT_BRIEF_DOCS = NO
+SORT_BY_SCOPE_NAME = NO
+GENERATE_TODOLIST = YES
+GENERATE_TESTLIST = YES
+GENERATE_BUGLIST = YES
+GENERATE_DEPRECATEDLIST= YES
+ENABLED_SECTIONS =
+MAX_INITIALIZER_LINES = 30
+SHOW_USED_FILES = YES
+SHOW_DIRECTORIES = NO
+FILE_VERSION_FILTER =
+#---------------------------------------------------------------------------
+# configuration options related to warning and progress messages
+#---------------------------------------------------------------------------
+QUIET = NO
+WARNINGS = YES
+WARN_IF_UNDOCUMENTED = YES
+WARN_IF_DOC_ERROR = YES
+WARN_NO_PARAMDOC = NO
+WARN_FORMAT = "$file:$line: $text"
+WARN_LOGFILE =
+#---------------------------------------------------------------------------
+# configuration options related to the input files
+#---------------------------------------------------------------------------
+INPUT = ../
+FILE_PATTERNS = *.c *.cpp *.h *.cc *.hh *.py
+RECURSIVE = YES
+EXCLUDE =
+EXCLUDE_SYMLINKS = NO
+EXCLUDE_PATTERNS =
+EXAMPLE_PATH =
+EXAMPLE_PATTERNS =
+EXAMPLE_RECURSIVE = NO
+IMAGE_PATH =
+INPUT_FILTER =
+FILTER_PATTERNS =
+FILTER_SOURCE_FILES = NO
+#---------------------------------------------------------------------------
+# configuration options related to source browsing
+#---------------------------------------------------------------------------
+SOURCE_BROWSER = NO
+INLINE_SOURCES = NO
+STRIP_CODE_COMMENTS = YES
+REFERENCED_BY_RELATION = NO
+REFERENCES_RELATION = NO
+REFERENCES_LINK_SOURCE = YES
+USE_HTAGS = NO
+VERBATIM_HEADERS = NO
+#---------------------------------------------------------------------------
+# configuration options related to the alphabetical class index
+#---------------------------------------------------------------------------
+ALPHABETICAL_INDEX = NO
+COLS_IN_ALPHA_INDEX = 5
+IGNORE_PREFIX =
+#---------------------------------------------------------------------------
+# configuration options related to the HTML output
+#---------------------------------------------------------------------------
+GENERATE_HTML = YES
+HTML_OUTPUT = html
+HTML_FILE_EXTENSION = .html
+HTML_HEADER =
+HTML_FOOTER =
+HTML_STYLESHEET =
+HTML_ALIGN_MEMBERS = YES
+GENERATE_HTMLHELP = NO
+CHM_FILE =
+HHC_LOCATION =
+GENERATE_CHI = NO
+BINARY_TOC = NO
+TOC_EXPAND = NO
+DISABLE_INDEX = NO
+ENUM_VALUES_PER_LINE = 4
+GENERATE_TREEVIEW = NO
+TREEVIEW_WIDTH = 250
+#---------------------------------------------------------------------------
+# configuration options related to the LaTeX output
+#---------------------------------------------------------------------------
+GENERATE_LATEX = YES
+LATEX_OUTPUT = latex
+LATEX_CMD_NAME = latex
+MAKEINDEX_CMD_NAME = makeindex
+COMPACT_LATEX = NO
+PAPER_TYPE = a4wide
+EXTRA_PACKAGES =
+LATEX_HEADER =
+PDF_HYPERLINKS = NO
+USE_PDFLATEX = NO
+LATEX_BATCHMODE = NO
+LATEX_HIDE_INDICES = NO
+#---------------------------------------------------------------------------
+# configuration options related to the RTF output
+#---------------------------------------------------------------------------
+GENERATE_RTF = NO
+RTF_OUTPUT = rtf
+COMPACT_RTF = NO
+RTF_HYPERLINKS = NO
+RTF_STYLESHEET_FILE =
+RTF_EXTENSIONS_FILE =
+#---------------------------------------------------------------------------
+# configuration options related to the man page output
+#---------------------------------------------------------------------------
+GENERATE_MAN = NO
+MAN_OUTPUT = man
+MAN_EXTENSION = .3
+MAN_LINKS = NO
+#---------------------------------------------------------------------------
+# configuration options related to the XML output
+#---------------------------------------------------------------------------
+GENERATE_XML = NO
+XML_OUTPUT = xml
+XML_SCHEMA =
+XML_DTD =
+XML_PROGRAMLISTING = YES
+#---------------------------------------------------------------------------
+# configuration options for the AutoGen Definitions output
+#---------------------------------------------------------------------------
+GENERATE_AUTOGEN_DEF = NO
+#---------------------------------------------------------------------------
+# configuration options related to the Perl module output
+#---------------------------------------------------------------------------
+GENERATE_PERLMOD = NO
+PERLMOD_LATEX = NO
+PERLMOD_PRETTY = YES
+PERLMOD_MAKEVAR_PREFIX =
+#---------------------------------------------------------------------------
+# Configuration options related to the preprocessor
+#---------------------------------------------------------------------------
+ENABLE_PREPROCESSING = YES
+MACRO_EXPANSION = NO
+EXPAND_ONLY_PREDEF = NO
+SEARCH_INCLUDES = YES
+INCLUDE_PATH =
+INCLUDE_FILE_PATTERNS =
+PREDEFINED =
+EXPAND_AS_DEFINED =
+SKIP_FUNCTION_MACROS = YES
+#---------------------------------------------------------------------------
+# Configuration::additions related to external references
+#---------------------------------------------------------------------------
+TAGFILES =
+GENERATE_TAGFILE =
+ALLEXTERNALS = NO
+EXTERNAL_GROUPS = YES
+PERL_PATH = /usr/bin/perl
+#---------------------------------------------------------------------------
+# Configuration options related to the dot tool
+#---------------------------------------------------------------------------
+CLASS_DIAGRAMS = NO
+HIDE_UNDOC_RELATIONS = YES
+HAVE_DOT = YES
+CLASS_GRAPH = YES
+COLLABORATION_GRAPH = YES
+GROUP_GRAPHS = YES
+UML_LOOK = NO
+TEMPLATE_RELATIONS = NO
+INCLUDE_GRAPH = YES
+INCLUDED_BY_GRAPH = YES
+CALL_GRAPH = NO
+CALLER_GRAPH = NO
+GRAPHICAL_HIERARCHY = YES
+DIRECTORY_GRAPH = YES
+DOT_IMAGE_FORMAT = png
+DOT_PATH =
+DOTFILE_DIRS =
+MAX_DOT_GRAPH_WIDTH = 1024
+MAX_DOT_GRAPH_HEIGHT = 1024
+MAX_DOT_GRAPH_DEPTH = 0
+DOT_TRANSPARENT = NO
+DOT_MULTI_TARGETS = NO
+GENERATE_LEGEND = YES
+DOT_CLEANUP = YES
+#---------------------------------------------------------------------------
+# Configuration::additions related to the search engine
+#---------------------------------------------------------------------------
+SEARCHENGINE = NO
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mm...@us...> - 2008-05-06 00:15:31
|
Revision: 315
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=315&view=rev
Author: mmwise
Date: 2008-05-05 17:15:38 -0700 (Mon, 05 May 2008)
Log Message:
-----------
added README for docs
Modified Paths:
--------------
pkg/trunk/util/control/auto_calibration/src/AutoCal.cpp
pkg/trunk/util/control/auto_calibration/test/test_AutoCal.cpp
Added Paths:
-----------
pkg/trunk/README
Added: pkg/trunk/README
===================================================================
--- pkg/trunk/README (rev 0)
+++ pkg/trunk/README 2008-05-06 00:15:38 UTC (rev 315)
@@ -0,0 +1 @@
+To make the documentation go into documentation and make.
Modified: pkg/trunk/util/control/auto_calibration/src/AutoCal.cpp
===================================================================
--- pkg/trunk/util/control/auto_calibration/src/AutoCal.cpp 2008-05-05 23:48:01 UTC (rev 314)
+++ pkg/trunk/util/control/auto_calibration/src/AutoCal.cpp 2008-05-06 00:15:38 UTC (rev 315)
@@ -22,7 +22,7 @@
// Info for arm stage
- Info shoulder = {0, 180.0, 0.0, 0.0, -90.0, 90.0, 0, 0, 1000};
+ Info shoulder = {0, 180.0, 0.0, 0.0, -90.0, 90.0, 0, 1, 1000};
XmlRpcValue arm;
shoulder.toXmlRpcValue(arm["shoulder"]);
@@ -40,7 +40,7 @@
void AutoCal::RunAutoCal(string objectName)
{
- int speed = 125;
+ int speed = 70;
int flag = 1;
int count = 0;
@@ -50,13 +50,20 @@
cout << "Now auto calibrating " << object.size() <<" motors." << endl;
- e.motors_on();
- e.set_control_mode(0);
+ if (e.set_control_mode(0))
+ cout << "Control mode set to 0" << endl;
+ if (e.motors_on())
+ cout << "Motors turned on" << endl;
for (XmlRpcValue::iterator it2 = object.begin(); it2 != object.end(); ++it2)
{
+ //cout << "XmlRpcValue size: " << (*it2).second.size() << endl;
if (info.fromXmlRpcValue(it2)) {
+
+ //cout<<"here"<<endl;
e.set_drv(info.motorNum, speed);
+ e.tick();
+ cout<<e.get_cur(info.motorNum)<<endl;
}
}
@@ -74,42 +81,43 @@
{
if (info.fromXmlRpcValue(it2))
{
- if(e.get_cur(info.motorNum)>425 && info.count>999)
- {
- e.set_drv(info.motorNum, 0);
-
- if(info.flag == 1)
- {
- info.maxEncoder = e.get_enc(info.motorNum);
- info.flag = 0;
- info.count = 0;
- }
- else if(info.flag == -1)
- {
- info.minEncoder = e.get_enc(info.motorNum);
- info.flag = -2;
- }
- }
- else if(info.flag==0)
- {
- e.set_drv(info.motorNum, -speed);
- info.flag = -1;
- }
- else if(info.flag == -2)
- {
- count = count+1;
- info.flag = -3;
-
- }
- if(count==object.size())
- {
- flag=0;
- e.motors_off();
- cout << "Done calibrating " << object.size() <<" motors." << endl;
-
- }
- info.count = info.count +1;
- info.toXmlRpcValue(it2);
+
+ if(e.get_cur(info.motorNum)>400 && info.count>50)
+ {
+ e.set_drv(info.motorNum, 0);
+
+ if(info.flag == 1)
+ {
+ info.maxEncoder = e.get_enc(info.motorNum);
+ info.flag = 0;
+ info.count = 0;
+ }
+ else if(info.flag == -1)
+ {
+ info.minEncoder = e.get_enc(info.motorNum);
+ info.flag = -2;
+ }
+ }
+ else if(info.flag==0 && info.count>50)
+ {
+ e.set_drv(info.motorNum, -speed);
+ info.flag = -1;
+ info.count=0;
+ }
+ else if(info.flag == -2)
+ {
+ count = count+1;
+ info.flag = -3;
+
+ }
+ if(count==object.size())
+ {
+ flag=0;
+ e.motors_off();
+ cout << "Done calibrating " << object.size() <<" motors." << endl;
+ }
+ info.count = info.count +1;
+ info.toXmlRpcValue(it2);
}
usleep(300);
}
@@ -117,7 +125,8 @@
for (XmlRpcValue::iterator it2 = object.begin(); it2 != object.end(); ++it2)
{
- if (info.fromXmlRpcValue(it2)) {
+ if (info.fromXmlRpcValue(it2))
+ {
cout << "Min Encoder : " << info.minEncoder << " Max Encoder : "<< info.maxEncoder << endl;
}
}
Modified: pkg/trunk/util/control/auto_calibration/test/test_AutoCal.cpp
===================================================================
--- pkg/trunk/util/control/auto_calibration/test/test_AutoCal.cpp 2008-05-05 23:48:01 UTC (rev 314)
+++ pkg/trunk/util/control/auto_calibration/test/test_AutoCal.cpp 2008-05-06 00:15:38 UTC (rev 315)
@@ -28,9 +28,11 @@
int main(int argc, char **argv)
{
ros::init(argc, argv);
+
Test_Autocal T;
T.run();
return 1;
+
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-05-06 16:16:09
|
Revision: 316
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=316&view=rev
Author: gerkey
Date: 2008-05-06 09:15:56 -0700 (Tue, 06 May 2008)
Log Message:
-----------
fixed for OS X build
Modified Paths:
--------------
pkg/trunk/3rdparty/sdl/manifest.xml
pkg/trunk/util/gui/sdlgl/include/sdlgl/sdlgl.h
pkg/trunk/util/gui/sdlgl/manifest.xml
Modified: pkg/trunk/3rdparty/sdl/manifest.xml
===================================================================
--- pkg/trunk/3rdparty/sdl/manifest.xml 2008-05-06 00:15:38 UTC (rev 315)
+++ pkg/trunk/3rdparty/sdl/manifest.xml 2008-05-06 16:15:56 UTC (rev 316)
@@ -11,7 +11,8 @@
<license>LGPL</license>
<url>http://www.libsdl.org</url>
<export>
- <cpp lflags="-Xlinker -rpath ${prefix}/SDL/lib -L${prefix}/SDL/lib -lSDL" cflags="-I${prefix}/SDL/include"/>
+ <!-- <cpp lflags="-Xlinker -rpath ${prefix}/SDL/lib -L${prefix}/SDL/lib -lSDL" cflags="-I${prefix}/SDL/include"/> -->
+ <cpp lflags="`${prefix}/SDL/bin/sdl-config --libs`" cflags="`${prefix}/SDL/bin/sdl-config --cflags`"/>
</export>
</package>
Modified: pkg/trunk/util/gui/sdlgl/include/sdlgl/sdlgl.h
===================================================================
--- pkg/trunk/util/gui/sdlgl/include/sdlgl/sdlgl.h 2008-05-06 00:15:38 UTC (rev 315)
+++ pkg/trunk/util/gui/sdlgl/include/sdlgl/sdlgl.h 2008-05-06 16:15:56 UTC (rev 316)
@@ -1,7 +1,8 @@
#ifndef SDLGL_SDLGL_H
#define SDLGL_SDLGL_H
-#include <SDL/SDL.h>
+//#include <SDL/SDL.h>
+#include <SDL.h>
namespace ros
{
Modified: pkg/trunk/util/gui/sdlgl/manifest.xml
===================================================================
--- pkg/trunk/util/gui/sdlgl/manifest.xml 2008-05-06 00:15:38 UTC (rev 315)
+++ pkg/trunk/util/gui/sdlgl/manifest.xml 2008-05-06 16:15:56 UTC (rev 316)
@@ -1,6 +1,11 @@
<package>
<depend package="sdl"/>
<export>
- <cpp cflags="-I${prefix}/include" lflags="-L${prefix}/lib -lsdlgl -lGL -lGLU"/>
+ <cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lsdlgl -lGL -lGLU"/>
+ <!-- The usage of -dylib_file is a workaround for a bug in Apple's
+ installation of libGL.dylib, as explained here:
+ http://developer.apple.com/qa/qa2007/qa1567.html
+ -->
+ <cpp os="osx" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -framework OpenGL -L/usr/X11R6/lib -dylib_file /System/Library/Frameworks/OpenGL.framework/Versions/A/Libraries/libGL.dylib:/System/Library/Frameworks/OpenGL.framework/Versions/A/Libraries/libGL.dylib -lsdlgl -lGL -lGLU" cflags="-I/usr/X11R6/include -I${prefix}/include"/>
</export>
</package>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-05-07 22:17:27
|
Revision: 346
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=346&view=rev
Author: gerkey
Date: 2008-05-07 15:17:30 -0700 (Wed, 07 May 2008)
Log Message:
-----------
modified message references in various nodes
Modified Paths:
--------------
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/wavefront_player/manifest.xml
pkg/trunk/nav/wavefront_player/wavefront_player.cc
Added Paths:
-----------
pkg/trunk/drivers/robot/erratic_player/
pkg/trunk/drivers/robot/erratic_player/Makefile
pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
pkg/trunk/drivers/robot/erratic_player/manifest.xml
Removed Paths:
-------------
pkg/trunk/drivers/robot/erratic_player/Makefile
pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
pkg/trunk/drivers/robot/erratic_player/manifest.xml
pkg/trunk/unported/erratic_player/
Copied: pkg/trunk/drivers/robot/erratic_player (from rev 340, pkg/trunk/unported/erratic_player)
Deleted: pkg/trunk/drivers/robot/erratic_player/Makefile
===================================================================
--- pkg/trunk/unported/erratic_player/Makefile 2008-05-07 17:44:26 UTC (rev 340)
+++ pkg/trunk/drivers/robot/erratic_player/Makefile 2008-05-07 22:17:30 UTC (rev 346)
@@ -1,12 +0,0 @@
-PKG = erratic_player
-CXX = g++
-all: $(PKG)
-
-CFLAGS = -g -Wall -Werror `rospack export/cpp/cflags $(PKG)`
-LFLAGS = `rospack export/cpp/lflags $(PKG)`
-
-erratic_player: erratic_player.cc
- $(CXX) $(CFLAGS) -o $@ $< $(LFLAGS)
-
-clean:
- rm -f *.o $(PKG)
Copied: pkg/trunk/drivers/robot/erratic_player/Makefile (from rev 345, pkg/trunk/unported/erratic_player/Makefile)
===================================================================
--- pkg/trunk/drivers/robot/erratic_player/Makefile (rev 0)
+++ pkg/trunk/drivers/robot/erratic_player/Makefile 2008-05-07 22:17:30 UTC (rev 346)
@@ -0,0 +1,12 @@
+PKG = erratic_player
+CXX = g++
+all: $(PKG)
+
+CFLAGS = -g -Wall -Werror `rospack export/cpp/cflags $(PKG)`
+LFLAGS = `rospack export/cpp/lflags $(PKG)`
+
+erratic_player: erratic_player.cc
+ $(CXX) $(CFLAGS) -o $@ $< $(LFLAGS)
+
+clean:
+ rm -f *.o $(PKG)
Deleted: pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
===================================================================
--- pkg/trunk/unported/erratic_player/erratic_player.cc 2008-05-07 17:44:26 UTC (rev 340)
+++ pkg/trunk/drivers/robot/erratic_player/erratic_player.cc 2008-05-07 22:17:30 UTC (rev 346)
@@ -1,222 +0,0 @@
-#include <assert.h>
-
-// For core Player stuff (message queues, config file objects, etc.)
-#include <libplayercore/playercore.h>
-// TODO: remove XDR dependency
-#include <libplayerxdr/playerxdr.h>
-
-// roscpp
-#include <ros/node.h>
-// Messages that I need
-#include <std_msgs/MsgRobotBase2DOdom.h>
-#include <std_msgs/MsgRobotBase2DCmdVel.h>
-
-#define PLAYER_QUEUE_LEN 32
-
-// Must prototype this function here. It's implemented inside
-// libplayerdrivers.
-Driver* Erratic_Init(ConfigFile* cf, int section);
-
-class ErraticNode: public ros::node
-{
- public:
- QueuePointer q;
-
- MsgRobotBase2DOdom odom;
- MsgRobotBase2DCmdVel cmdvel;
-
- ErraticNode() : ros::node("erratic")
- {
- advertise<MsgRobotBase2DOdom>("odom");
- subscribe("cmdvel", cmdvel, &ErraticNode::cmdvelReceived);
-
- // libplayercore boiler plate
- player_globals_init();
- itable_init();
-
- // TODO: remove XDR dependency
- playerxdr_ftable_init();
-
- // The Player address that will be assigned to this device. The format
- // is interface:index. The interface must match what the driver is
- // expecting to provide. The value of the index doesn't really matter,
- // but 0 is most common.
- const char* player_addr = "position2d:0";
-
- // Create a ConfigFile object, into which we'll stuff parameters.
- // Drivers assume that this object will persist throughout execution
- // (e.g., they store pointers to data inside it). So it must NOT be
- // deleted until after the driver is shut down.
- this->cf = new ConfigFile();
-
- // Insert (name,value) pairs into the ConfigFile object. These would
- // presumably come from the param server
- this->cf->InsertFieldValue(0,"provides",player_addr);
- this->cf->InsertFieldValue(0,"port","/dev/ttyUSB0");
-
- // Create an instance of the driver, passing it the ConfigFile object.
- // The -1 tells it to look into the "global" section of the ConfigFile,
- // which is where ConfigFile::InsertFieldValue() put the parameters.
- assert((this->driver = Erratic_Init(cf, -1)));
-
- // Print out warnings about parameters that were set, but which the
- // driver never looked at.
- cf->WarnUnused();
-
- // Grab from the global deviceTable a pointer to the Device that was
- // created as part of the driver's initialization.
- assert((this->device = deviceTable->GetDevice(player_addr,false)));
-
- // Create a message queue
- this->q = QueuePointer(false,PLAYER_QUEUE_LEN);
- }
-
- ~ErraticNode()
- {
- delete driver;
- delete cf;
- player_globals_fini();
- }
-
- int start()
- {
- // Subscribe to device, which causes it to startup
- if(this->device->Subscribe(this->q) != 0)
- {
- puts("Failed to subscribe the driver");
- return(-1);
- }
- else
- return(0);
- }
-
- int stop()
- {
- // Unsubscribe from the device, which causes it to shutdown
- if(device->Unsubscribe(this->q) != 0)
- {
- puts("Failed to start the driver");
- return(-1);
- }
- else
- return(0);
- }
-
- int setMotorState(uint8_t state)
- {
- Message* msg;
- // Enable the motors
- player_position2d_power_config_t motorconfig;
- motorconfig.state = state;
- if(!(msg = this->device->Request(this->q,
- PLAYER_MSGTYPE_REQ,
- PLAYER_POSITION2D_REQ_MOTOR_POWER,
- (void*)&motorconfig,
- sizeof(motorconfig), NULL, false)))
- {
- return(-1);
- }
- else
- {
- delete msg;
- return(0);
- }
- }
-
- void cmdvelReceived()
- {
- printf("received cmd: (%.3f,%.3f,%.3f)\n",
- this->cmdvel.vx,
- this->cmdvel.vy,
- this->cmdvel.vyaw);
-
- player_position2d_cmd_vel_t cmd;
- memset(&cmd, 0, sizeof(cmd));
-
- cmd.vel.px = this->cmdvel.vx;
- cmd.vel.py = this->cmdvel.vy;
- cmd.vel.pa = this->cmdvel.vyaw;
- cmd.state = 1;
-
- this->device->PutMsg(this->q,
- PLAYER_MSGTYPE_CMD,
- PLAYER_POSITION2D_CMD_VEL,
- (void*)&cmd,sizeof(cmd),NULL);
- }
-
- private:
- Driver* driver;
- Device* device;
- ConfigFile* cf;
-};
-
-int
-main(int argc, char** argv)
-{
- ros::init(argc, argv);
-
- ErraticNode en;
- Message* msg;
-
- // Start up the robot
- if(en.start() != 0)
- exit(-1);
-
- // Enable the motors
- if(en.setMotorState(1) < 0)
- puts("failed to enable motors");
-
- /////////////////////////////////////////////////////////////////
- // Main loop; grab messages off our queue and republish them via ROS
- for(;;)
- {
- // Block until there's a message on the queue
- en.q->Wait();
-
- // Pop off one message (we own the resulting memory)
- assert((msg = en.q->Pop()));
-
- // Is the message one we care about?
- player_msghdr_t* hdr = msg->GetHeader();
- if((hdr->type == PLAYER_MSGTYPE_DATA) &&
- (hdr->subtype == PLAYER_POSITION2D_DATA_STATE))
- {
- // Cast the message payload appropriately
- player_position2d_data_t* pdata = (player_position2d_data_t*)msg->GetPayload();
-
- // Translate from Player data to ROS data
- en.odom.px = pdata->pos.px;
- en.odom.py = pdata->pos.py;
- en.odom.pyaw = pdata->pos.pa;
- en.odom.vx = pdata->vel.px;
- en.odom.vy = pdata->vel.py;
- en.odom.vyaw = pdata->vel.pa;
- en.odom.stall = pdata->stall;
-
- // Publish the new data
- en.publish("odom", en.odom);
-
- printf("Published new odom: (%.3f,%.3f,%.3f)\n",
- en.odom.px, en.odom.py, en.odom.pyaw);
- }
- else
- {
- printf("Unhandled Player message %d:%d:%d:%d\n",
- hdr->type,
- hdr->subtype,
- hdr->addr.interf,
- hdr->addr.index);
-
- }
-
- // We're done with the message now
- delete msg;
- }
- /////////////////////////////////////////////////////////////////
-
- // Stop the robot
- en.stop();
-
- // To quote Morgan, Hooray!
- return(0);
-}
Copied: pkg/trunk/drivers/robot/erratic_player/erratic_player.cc (from rev 345, pkg/trunk/unported/erratic_player/erratic_player.cc)
===================================================================
--- pkg/trunk/drivers/robot/erratic_player/erratic_player.cc (rev 0)
+++ pkg/trunk/drivers/robot/erratic_player/erratic_player.cc 2008-05-07 22:17:30 UTC (rev 346)
@@ -0,0 +1,222 @@
+#include <assert.h>
+
+// For core Player stuff (message queues, config file objects, etc.)
+#include <libplayercore/playercore.h>
+// TODO: remove XDR dependency
+#include <libplayerxdr/playerxdr.h>
+
+// roscpp
+#include <ros/node.h>
+// Messages that I need
+#include <std_msgs/MsgRobotBase2DOdom.h>
+#include <std_msgs/MsgRobotBase2DCmdVel.h>
+
+#define PLAYER_QUEUE_LEN 32
+
+// Must prototype this function here. It's implemented inside
+// libplayerdrivers.
+Driver* Erratic_Init(ConfigFile* cf, int section);
+
+class ErraticNode: public ros::node
+{
+ public:
+ QueuePointer q;
+
+ MsgRobotBase2DOdom odom;
+ MsgRobotBase2DCmdVel cmdvel;
+
+ ErraticNode() : ros::node("erratic")
+ {
+ advertise<MsgRobotBase2DOdom>("odom");
+ subscribe("cmdvel", cmdvel, &ErraticNode::cmdvelReceived);
+
+ // libplayercore boiler plate
+ player_globals_init();
+ itable_init();
+
+ // TODO: remove XDR dependency
+ playerxdr_ftable_init();
+
+ // The Player address that will be assigned to this device. The format
+ // is interface:index. The interface must match what the driver is
+ // expecting to provide. The value of the index doesn't really matter,
+ // but 0 is most common.
+ const char* player_addr = "position2d:0";
+
+ // Create a ConfigFile object, into which we'll stuff parameters.
+ // Drivers assume that this object will persist throughout execution
+ // (e.g., they store pointers to data inside it). So it must NOT be
+ // deleted until after the driver is shut down.
+ this->cf = new ConfigFile();
+
+ // Insert (name,value) pairs into the ConfigFile object. These would
+ // presumably come from the param server
+ this->cf->InsertFieldValue(0,"provides",player_addr);
+ this->cf->InsertFieldValue(0,"port","/dev/ttyUSB0");
+
+ // Create an instance of the driver, passing it the ConfigFile object.
+ // The -1 tells it to look into the "global" section of the ConfigFile,
+ // which is where ConfigFile::InsertFieldValue() put the parameters.
+ assert((this->driver = Erratic_Init(cf, -1)));
+
+ // Print out warnings about parameters that were set, but which the
+ // driver never looked at.
+ cf->WarnUnused();
+
+ // Grab from the global deviceTable a pointer to the Device that was
+ // created as part of the driver's initialization.
+ assert((this->device = deviceTable->GetDevice(player_addr,false)));
+
+ // Create a message queue
+ this->q = QueuePointer(false,PLAYER_QUEUE_LEN);
+ }
+
+ ~ErraticNode()
+ {
+ delete driver;
+ delete cf;
+ player_globals_fini();
+ }
+
+ int start()
+ {
+ // Subscribe to device, which causes it to startup
+ if(this->device->Subscribe(this->q) != 0)
+ {
+ puts("Failed to subscribe the driver");
+ return(-1);
+ }
+ else
+ return(0);
+ }
+
+ int stop()
+ {
+ // Unsubscribe from the device, which causes it to shutdown
+ if(device->Unsubscribe(this->q) != 0)
+ {
+ puts("Failed to start the driver");
+ return(-1);
+ }
+ else
+ return(0);
+ }
+
+ int setMotorState(uint8_t state)
+ {
+ Message* msg;
+ // Enable the motors
+ player_position2d_power_config_t motorconfig;
+ motorconfig.state = state;
+ if(!(msg = this->device->Request(this->q,
+ PLAYER_MSGTYPE_REQ,
+ PLAYER_POSITION2D_REQ_MOTOR_POWER,
+ (void*)&motorconfig,
+ sizeof(motorconfig), NULL, false)))
+ {
+ return(-1);
+ }
+ else
+ {
+ delete msg;
+ return(0);
+ }
+ }
+
+ void cmdvelReceived()
+ {
+ printf("received cmd: (%.3f,%.3f,%.3f)\n",
+ this->cmdvel.vel.x,
+ this->cmdvel.vel.y,
+ this->cmdvel.vel.th);
+
+ player_position2d_cmd_vel_t cmd;
+ memset(&cmd, 0, sizeof(cmd));
+
+ cmd.vel.px = this->cmdvel.vel.x;
+ cmd.vel.py = this->cmdvel.vel.y;
+ cmd.vel.pa = this->cmdvel.vel.th;
+ cmd.state = 1;
+
+ this->device->PutMsg(this->q,
+ PLAYER_MSGTYPE_CMD,
+ PLAYER_POSITION2D_CMD_VEL,
+ (void*)&cmd,sizeof(cmd),NULL);
+ }
+
+ private:
+ Driver* driver;
+ Device* device;
+ ConfigFile* cf;
+};
+
+int
+main(int argc, char** argv)
+{
+ ros::init(argc, argv);
+
+ ErraticNode en;
+ Message* msg;
+
+ // Start up the robot
+ if(en.start() != 0)
+ exit(-1);
+
+ // Enable the motors
+ if(en.setMotorState(1) < 0)
+ puts("failed to enable motors");
+
+ /////////////////////////////////////////////////////////////////
+ // Main loop; grab messages off our queue and republish them via ROS
+ for(;;)
+ {
+ // Block until there's a message on the queue
+ en.q->Wait();
+
+ // Pop off one message (we own the resulting memory)
+ assert((msg = en.q->Pop()));
+
+ // Is the message one we care about?
+ player_msghdr_t* hdr = msg->GetHeader();
+ if((hdr->type == PLAYER_MSGTYPE_DATA) &&
+ (hdr->subtype == PLAYER_POSITION2D_DATA_STATE))
+ {
+ // Cast the message payload appropriately
+ player_position2d_data_t* pdata = (player_position2d_data_t*)msg->GetPayload();
+
+ // Translate from Player data to ROS data
+ en.odom.pos.x = pdata->pos.px;
+ en.odom.pos.y = pdata->pos.py;
+ en.odom.pos.th = pdata->pos.pa;
+ en.odom.vel.x = pdata->vel.px;
+ en.odom.vel.y = pdata->vel.py;
+ en.odom.vel.th = pdata->vel.pa;
+ en.odom.stall = pdata->stall;
+
+ // Publish the new data
+ en.publish("odom", en.odom);
+
+ printf("Published new odom: (%.3f,%.3f,%.3f)\n",
+ en.odom.pos.x, en.odom.pos.y, en.odom.pos.th);
+ }
+ else
+ {
+ printf("Unhandled Player message %d:%d:%d:%d\n",
+ hdr->type,
+ hdr->subtype,
+ hdr->addr.interf,
+ hdr->addr.index);
+
+ }
+
+ // We're done with the message now
+ delete msg;
+ }
+ /////////////////////////////////////////////////////////////////
+
+ // Stop the robot
+ en.stop();
+
+ // To quote Morgan, Hooray!
+ return(0);
+}
Deleted: pkg/trunk/drivers/robot/erratic_player/manifest.xml
===================================================================
--- pkg/trunk/unported/erratic_player/manifest.xml 2008-05-07 17:44:26 UTC (rev 340)
+++ pkg/trunk/drivers/robot/erratic_player/manifest.xml 2008-05-07 22:17:30 UTC (rev 346)
@@ -1,8 +0,0 @@
-<package>
- <description>A ROS node that wraps up the Player erratic driver, which provides access to the Erratic mobile robot.</description>
- <author>Brian P. Gerkey</author>
- <license>BSD</license>
- <depend package="roscpp" />
- <depend package="player" />
- <depend package="std_msgs" />
-</package>
Copied: pkg/trunk/drivers/robot/erratic_player/manifest.xml (from rev 345, pkg/trunk/unported/erratic_player/manifest.xml)
===================================================================
--- pkg/trunk/drivers/robot/erratic_player/manifest.xml (rev 0)
+++ pkg/trunk/drivers/robot/erratic_player/manifest.xml 2008-05-07 22:17:30 UTC (rev 346)
@@ -0,0 +1,8 @@
+<package>
+ <description>A ROS node that wraps up the Player erratic driver, which provides access to the Erratic mobile robot.</description>
+ <author>Brian P. Gerkey</author>
+ <license>BSD</license>
+ <depend package="roscpp" />
+ <depend package="player" />
+ <depend package="std_msgs" />
+</package>
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2008-05-07 22:16:59 UTC (rev 345)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2008-05-07 22:17:30 UTC (rev 346)
@@ -201,19 +201,19 @@
(player_position2d_data_t*)data;
// Translate from Player data to ROS data
- this->odom.px = pdata->pos.px;
- this->odom.py = pdata->pos.py;
- this->odom.pyaw = pdata->pos.pa;
- this->odom.vx = pdata->vel.px;
- this->odom.vy = pdata->vel.py;
- this->odom.vyaw = pdata->vel.pa;
+ this->odom.pos.x = pdata->pos.px;
+ this->odom.pos.y = pdata->pos.py;
+ this->odom.pos.th = pdata->pos.pa;
+ this->odom.vel.x = pdata->vel.px;
+ this->odom.vel.y = pdata->vel.py;
+ this->odom.vel.th = pdata->vel.pa;
this->odom.stall = pdata->stall;
// Publish the new data
this->ros::node::publish("odom", this->odom);
printf("Published new odom: (%.3f,%.3f,%.3f)\n",
- this->odom.px, this->odom.py, this->odom.pyaw);
+ this->odom.pos.x, this->odom.pos.y, this->odom.pos.th);
return(0);
}
// Is it a request for the map metadata?
Modified: pkg/trunk/nav/wavefront_player/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront_player/manifest.xml 2008-05-07 22:16:59 UTC (rev 345)
+++ pkg/trunk/nav/wavefront_player/manifest.xml 2008-05-07 22:17:30 UTC (rev 346)
@@ -5,4 +5,5 @@
<depend package="roscpp" />
<depend package="player" />
<depend package="std_msgs" />
+ <depend package="rosTF" />
</package>
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-05-07 22:16:59 UTC (rev 345)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-05-07 22:17:30 UTC (rev 346)
@@ -8,6 +8,7 @@
#include <ros/node.h>
#include <std_msgs/MsgPlanner2DState.h>
#include <std_msgs/MsgPlanner2DGoal.h>
+#include <rosTF/rosTF.h>
// compute linear index for given map coords
#define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
@@ -48,6 +49,9 @@
void goalReceived();
public:
+ // Transform client
+ rosTFClient* tf;
+
WavefrontNode(char* fname, double res);
~WavefrontNode();
@@ -72,6 +76,7 @@
ros::init(argc,argv);
WavefrontNode wn(argv[1],atof(argv[2]));
+ wn.tf = new rosTFClient(wn);
while(wn.ok())
{
@@ -90,7 +95,8 @@
safety_dist(0.05),
max_radius(0.25),
dist_penalty(1.0),
- plan_halfwidth(5.0)
+ plan_halfwidth(5.0),
+ tf(NULL)
{
advertise<MsgPlanner2DState>("state");
subscribe("goal", goalMsg, &WavefrontNode::goalReceived);
@@ -139,7 +145,9 @@
WavefrontNode::~WavefrontNode()
{
- plan_free(plan);
+ plan_free(this->plan);
+ if(this->tf)
+ delete this->tf;
}
void
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-05-09 20:11:57
|
Revision: 376
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=376&view=rev
Author: gerkey
Date: 2008-05-09 13:11:38 -0700 (Fri, 09 May 2008)
Log Message:
-----------
Generalized Joy.msg to handle any number of axes and buttons, and store
their values as indexable arrays. Added 'deadzone' parameter to joy
node. Added 'axis_vx' and 'axis_vw' params to teleop_base node, to
allow runtime mapping of joystick axes to velocity axes. Added
'deadman_button' param to teleop_base to allow selection of deadman
button (-1 disables).
Modified Paths:
--------------
pkg/trunk/drivers/input/joy/joy.cpp
pkg/trunk/drivers/input/joy/msg/Joy.msg
pkg/trunk/nav/teleop_base/teleop_base.cpp
Modified: pkg/trunk/drivers/input/joy/joy.cpp
===================================================================
--- pkg/trunk/drivers/input/joy/joy.cpp 2008-05-09 19:14:05 UTC (rev 375)
+++ pkg/trunk/drivers/input/joy/joy.cpp 2008-05-09 20:11:38 UTC (rev 376)
@@ -5,6 +5,10 @@
#include "ros/node.h"
#include "joy/MsgJoy.h"
+// This should really go in the .msg
+#define MAX_BUTTONS 4
+#define MAX_AXES 4
+
void *s_joy_func(void *);
using namespace ros;
@@ -15,11 +19,14 @@
int joy_fd;
string joy_dev;
- int joy_buttons;
+ int deadzone;
- Joy() : node("joy"), joy_buttons(0)
+ Joy() : node("joy")
{
- param<string>("joy_dev", joy_dev, "/dev/input/js0");
+ param<string>("joy/dev", joy_dev, "/dev/input/js0");
+ param<int>("joy/deadzone", deadzone, 2000);
+ printf("dev:%s\n", joy_dev.c_str());
+ printf("deadzone:%d\n", deadzone);
joy_fd = open(joy_dev.c_str(), O_RDONLY);
if (joy_fd <= 0)
log(FATAL, "couldn't open joystick %s.", joy_dev.c_str());
@@ -39,22 +46,27 @@
switch(event.type)
{
case JS_EVENT_BUTTON:
- if (event.value)
- joy_buttons |= (1 << event.number);
+ if(event.number >= joy_msg.get_buttons_size())
+ {
+ joy_msg.set_buttons_size(event.number+1);
+ for(unsigned int i=0;i<joy_msg.get_buttons_size();i++)
+ joy_msg.buttons[i] = 0;
+ }
+ if(event.value)
+ joy_msg.buttons[event.number] = 1;
else
- joy_buttons &= ~(1 << event.number);
- joy_msg.buttons = joy_buttons;
+ joy_msg.buttons[event.number] = 0;
publish("joy", joy_msg);
break;
case JS_EVENT_AXIS:
- switch(event.number)
+ if(event.number >= joy_msg.get_axes_size())
{
- case 0: joy_msg.x1 = event.value / 32767.0; break;
- case 1: joy_msg.y1 = -event.value / 32767.0; break;
- case 2: joy_msg.x2 = event.value / 32767.0; break;
- case 3: joy_msg.y2 = -event.value / 32767.0; break;
- default: break;
+ joy_msg.set_axes_size(event.number+1);
+ for(unsigned int i=0;i<joy_msg.get_axes_size();i++)
+ joy_msg.axes[i] = 0.0;
}
+ joy_msg.axes[event.number] = (fabs(event.value) < deadzone) ? 0.0 :
+ (-event.value / 32767.0);
publish("joy", joy_msg);
break;
}
Modified: pkg/trunk/drivers/input/joy/msg/Joy.msg
===================================================================
--- pkg/trunk/drivers/input/joy/msg/Joy.msg 2008-05-09 19:14:05 UTC (rev 375)
+++ pkg/trunk/drivers/input/joy/msg/Joy.msg 2008-05-09 20:11:38 UTC (rev 376)
@@ -1,5 +1,2 @@
-float32 x1
-float32 y1
-float32 x2
-float32 y2
-int32 buttons
+float32[] axes
+int32[] buttons
Modified: pkg/trunk/nav/teleop_base/teleop_base.cpp
===================================================================
--- pkg/trunk/nav/teleop_base/teleop_base.cpp 2008-05-09 19:14:05 UTC (rev 375)
+++ pkg/trunk/nav/teleop_base/teleop_base.cpp 2008-05-09 20:11:38 UTC (rev 376)
@@ -12,6 +12,8 @@
MsgBaseVel cmd;
MsgJoy joy;
double req_vx, req_vw, max_vx, max_vw;
+ int axis_vx, axis_vw;
+ int deadman_button;
TeleopBase() : node("teleop_base"), max_vx(1), max_vw(1)
{
@@ -20,20 +22,47 @@
log(WARNING, "maximum linear velocity (max_vx) not set. Assuming 0.3");
if (!has_param("max_vw") || !get_param("max_vw", max_vx))
log(WARNING, "maximum angular velocity (max_vw) not set. Assuming 0.3");
+ param<int>("axis_vx", axis_vx, 1);
+ param<int>("axis_vw", axis_vw, 0);
+ param<int>("deadman_button", deadman_button, 0);
+
+ printf("max_vx: %.3f m/s\n", max_vx);
+ printf("max_vw: %.3f deg/s\n", max_vw*180.0/M_PI);
+ printf("axis_vx: %d\n", axis_vx);
+ printf("axis_vw: %d\n", axis_vw);
+ printf("deadman_button: %d\n", deadman_button);
+
advertise("cmd_vel", cmd);
subscribe("joy", joy, &TeleopBase::joy_cb);
}
void joy_cb()
{
joy.lock();
- req_vx = joy.y1 * max_vx;
- req_vw = -joy.x2 * max_vw;
+ printf("axes: ");
+ for(int i=0;i<joy.get_axes_size();i++)
+ printf("%.3f ", joy.axes[i]);
+ puts("");
+ printf("buttons: ");
+ for(int i=0;i<joy.get_buttons_size();i++)
+ printf("%d ", joy.buttons[i]);
+ puts("");
+
+ if((axis_vx >= 0) && (((unsigned int)axis_vx) < joy.get_axes_size()))
+ req_vx = joy.axes[axis_vx] * max_vx;
+ else
+ req_vx = 0.0;
+ if((axis_vw >= 0) && (((unsigned int)axis_vw) < joy.get_axes_size()))
+ req_vw = joy.axes[axis_vw] * max_vw;
+ else
+ req_vw = 0.0;
joy.unlock();
}
void send_cmd_vel()
{
joy.lock();
- if (joy.buttons & 0x20) // todo: pull the "deadman" button from a paramter
+ if((deadman_button < 0) ||
+ ((((unsigned int)deadman_button) < joy.get_buttons_size()) &&
+ joy.buttons[deadman_button]))
{
cmd.vx = req_vx;
cmd.vw = req_vw;
@@ -51,7 +80,7 @@
TeleopBase teleop_base;
while (teleop_base.ok())
{
- usleep(200000);
+ usleep(50000);
teleop_base.send_cmd_vel();
}
return 0;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-05-09 20:12:14
|
Revision: 377
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=377&view=rev
Author: gerkey
Date: 2008-05-09 13:12:13 -0700 (Fri, 09 May 2008)
Log Message:
-----------
fixed a variety of startup / shutdown bugs, moved erratic_player to use BaseVel message; basic joystick control works, and the particle filter is evolving
Modified Paths:
--------------
pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc
pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/wavefront_player/wavefront_player.cc
Modified: pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc
===================================================================
--- pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc 2008-05-09 20:11:38 UTC (rev 376)
+++ pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc 2008-05-09 20:12:13 UTC (rev 377)
@@ -83,7 +83,7 @@
return(numreadings);
}
- printf("%d readings\n", numreadings);
+ //printf("%d readings\n", numreadings);
scan.angle_min = cfg.min_angle;
scan.angle_max = cfg.max_angle;
Modified: pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
===================================================================
--- pkg/trunk/drivers/robot/erratic_player/erratic_player.cc 2008-05-09 20:11:38 UTC (rev 376)
+++ pkg/trunk/drivers/robot/erratic_player/erratic_player.cc 2008-05-09 20:12:13 UTC (rev 377)
@@ -9,7 +9,8 @@
#include <ros/node.h>
// Messages that I need
#include <std_msgs/MsgRobotBase2DOdom.h>
-#include <std_msgs/MsgRobotBase2DCmdVel.h>
+//#include <std_msgs/MsgRobotBase2DCmdVel.h>
+#include <std_msgs/MsgBaseVel.h>
#define PLAYER_QUEUE_LEN 32
@@ -23,20 +24,21 @@
QueuePointer q;
MsgRobotBase2DOdom odom;
- MsgRobotBase2DCmdVel cmdvel;
+ //MsgRobotBase2DCmdVel cmdvel;
+ MsgBaseVel cmdvel;
- ErraticNode() : ros::node("erratic")
+ ErraticNode() : ros::node("erratic_player")
{
- advertise<MsgRobotBase2DOdom>("odom");
- subscribe("cmdvel", cmdvel, &ErraticNode::cmdvelReceived);
-
// libplayercore boiler plate
player_globals_init();
+ puts("init");
itable_init();
// TODO: remove XDR dependency
playerxdr_ftable_init();
+ advertise<MsgRobotBase2DOdom>("odom");
+
// The Player address that will be assigned to this device. The format
// is interface:index. The interface must match what the driver is
// expecting to provide. The value of the index doesn't really matter,
@@ -86,7 +88,10 @@
return(-1);
}
else
+ {
+ subscribe("cmd_vel", cmdvel, &ErraticNode::cmdvelReceived);
return(0);
+ }
}
int stop()
@@ -129,19 +134,25 @@
void cmdvelReceived()
{
+ /*
printf("received cmd: (%.3f,%.3f,%.3f)\n",
this->cmdvel.vel.x,
this->cmdvel.vel.y,
this->cmdvel.vel.th);
+ */
player_position2d_cmd_vel_t cmd;
memset(&cmd, 0, sizeof(cmd));
- cmd.vel.px = this->cmdvel.vel.x;
- cmd.vel.py = this->cmdvel.vel.y;
- cmd.vel.pa = this->cmdvel.vel.th;
+ //cmd.vel.px = this->cmdvel.vel.x;
+ //cmd.vel.py = this->cmdvel.vel.y;
+ //cmd.vel.pa = this->cmdvel.vel.th;
+ cmd.vel.px = this->cmdvel.vx;
+ cmd.vel.py = 0.0;
+ cmd.vel.pa = this->cmdvel.vw;
cmd.state = 1;
+
this->device->PutMsg(this->q,
PLAYER_MSGTYPE_CMD,
PLAYER_POSITION2D_CMD_VEL,
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2008-05-09 20:11:38 UTC (rev 376)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2008-05-09 20:12:13 UTC (rev 377)
@@ -111,9 +111,16 @@
}
AmclNode::AmclNode(char* fname, double res) :
- ros::node("erratic"),
+ ros::node("amcl_player"),
Driver(NULL,-1,false,PLAYER_QUEUE_LEN)
{
+ // libplayercore boiler plate
+ player_globals_init();
+ itable_init();
+
+ // TODO: remove XDR dependency
+ playerxdr_ftable_init();
+
subscribe("odom", odomMsg, &AmclNode::odomReceived);
subscribe("scan", laserMsg, &AmclNode::laserReceived);
@@ -122,13 +129,6 @@
== 0);
this->resolution = res;
- // libplayercore boiler plate
- player_globals_init();
- itable_init();
-
- // TODO: remove XDR dependency
- playerxdr_ftable_init();
-
// TODO: automatically convert between string and player_devaddr_t
// representations
@@ -213,7 +213,6 @@
AmclNode::~AmclNode()
{
- delete this->driver;
delete this->cf;
player_globals_fini();
free(this->mapdata);
@@ -224,12 +223,6 @@
player_msghdr * hdr,
void * data)
{
- printf("Player message %d:%d:%d:%d\n",
- hdr->type,
- hdr->subtype,
- hdr->addr.interf,
- hdr->addr.index);
-
// Is it a new pose from amcl?
if(Message::MatchMessage(hdr,
PLAYER_MSGTYPE_DATA,
@@ -242,7 +235,10 @@
// publish new transform map->odom
//this->tf->sendEuler(5,count++,1,1,1,1,1,1,100000,100000);
- printf("got new pose");
+ printf("pose: (%.3f %.3f %.3f)\n",
+ pdata->pos.px,
+ pdata->pos.py,
+ RTOD(pdata->pos.pa));
return(0);
}
// Is it a request for the map metadata?
@@ -360,16 +356,28 @@
return(-1);
}
else
+ {
+ // Give the driver a chance to shutdown. Wish there were a way to
+ // detect when that happened.
+ usleep(1000000);
return(0);
+ }
}
int
AmclNode::process()
{
+ // Can't block here, because we won't exit cleanly. The Wait() call
+ // blocks on pthread_cond_wait(), which is a cancellation point, but in
+ // this case we're the main thread and noone will try to cancel us.
+ //
// Block until there's a message on our queue
- this->Driver::InQueue->Wait();
+ //this->Driver::InQueue->Wait();
- this->Driver::ProcessMessages();
+ if(!this->Driver::InQueue->Empty())
+ this->Driver::ProcessMessages();
+ else
+ usleep(1000000);
return(0);
}
@@ -398,11 +406,14 @@
double timestamp = this->odomMsg.header.stamp_secs +
this->odomMsg.header.stamp_nsecs / 1e9;
- this->device->PutMsg(this->Driver::InQueue,
- PLAYER_MSGTYPE_DATA,
- PLAYER_LASER_DATA_SCAN,
- (void*)&pdata,0,
- ×tamp);
+ this->Driver::Publish(this->laser_addr,
+ PLAYER_MSGTYPE_DATA,
+ PLAYER_LASER_DATA_SCAN,
+ (void*)&pdata,0,
+ ×tamp,true);
+
+ //delete[] pdata.ranges;
+ //delete[] pdata.intensity;
}
void
@@ -421,11 +432,11 @@
double timestamp = this->odomMsg.header.stamp_secs +
this->odomMsg.header.stamp_nsecs / 1e9;
- this->device->PutMsg(this->Driver::InQueue,
- PLAYER_MSGTYPE_DATA,
- PLAYER_POSITION2D_DATA_STATE,
- (void*)&pdata,0,
- ×tamp);
+ this->Driver::Publish(this->position2d_addr,
+ PLAYER_MSGTYPE_DATA,
+ PLAYER_POSITION2D_DATA_STATE,
+ (void*)&pdata,0,
+ ×tamp,true);
}
int
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-05-09 20:11:38 UTC (rev 376)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-05-09 20:12:13 UTC (rev 377)
@@ -25,8 +25,6 @@
#define RTOD(a) ((a)*180.0/M_PI)
#define SIGN(x) (((x) < 0.0) ? -1 : 1)
-// TODO: add mutexes around objects accessed by callbacks.
-
//void draw_cspace(plan_t* plan, const char* fname);
//void draw_path(plan_t* plan, double lx, double ly, const char* fname);
#include <gdk-pixbuf/gdk-pixbuf.h>
@@ -133,6 +131,7 @@
gettimeofday(&curr,NULL);
wn.doOneCycle();
wn.sleep(curr.tv_sec+curr.tv_usec/1e6);
+ puts("slept");
}
return(0);
}
@@ -267,14 +266,19 @@
}
}
+// Declare this globally, so that it never gets desctructed (message
+// desctruction causes master disconnect)
+MsgRobotBase2DCmdVel* cmdvel;
+
void
WavefrontNode::sendVelCmd(double vx, double vy, double vth)
{
- MsgRobotBase2DCmdVel cmdvel;
- cmdvel.vel.x = vx;
- cmdvel.vel.y = vy;
- cmdvel.vel.th = vth;
- this->ros::node::publish("cmdvel", cmdvel);
+ if(!cmdvel)
+ cmdvel = new MsgRobotBase2DCmdVel();
+ cmdvel->vel.x = vx;
+ cmdvel->vel.y = vy;
+ cmdvel->vel.th = vth;
+ this->ros::node::publish("cmdvel", *cmdvel);
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-05-09 22:27:37
|
Revision: 380
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=380&view=rev
Author: gerkey
Date: 2008-05-09 15:27:43 -0700 (Fri, 09 May 2008)
Log Message:
-----------
simple demo is working with localization; no transform happiness yet
Modified Paths:
--------------
pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/wavefront_player/wavefront_player.cc
Modified: pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
===================================================================
--- pkg/trunk/drivers/robot/erratic_player/erratic_player.cc 2008-05-09 20:54:09 UTC (rev 379)
+++ pkg/trunk/drivers/robot/erratic_player/erratic_player.cc 2008-05-09 22:27:43 UTC (rev 380)
@@ -208,6 +208,8 @@
en.odom.vel.th = pdata->vel.pa;
en.odom.stall = pdata->stall;
+ en.odom.header.frame_id = 2;
+
// Publish the new data
en.publish("odom", en.odom);
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2008-05-09 20:54:09 UTC (rev 379)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2008-05-09 22:27:43 UTC (rev 380)
@@ -247,7 +247,17 @@
(player_position2d_data_t*)data;
// publish new transform map->odom
- //this->tf->sendEuler(5,count++,1,1,1,1,1,1,100000,100000);
+ this->tf->sendEuler(2,1,
+ this->odomMsg.pos.x-pdata->pos.px,
+ this->odomMsg.pos.y-pdata->pos.py,
+ 0.0,
+ this->odomMsg.pos.th-pdata->pos.pa,
+ 0.0,
+ 0.0,
+ (unsigned int)floor(hdr->timestamp),
+ (unsigned int)((hdr->timestamp - floor(hdr->timestamp)) * 1e9));
+
+
printf("pose: (%.3f %.3f %.3f)\n",
pdata->pos.px,
pdata->pos.py,
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-05-09 20:54:09 UTC (rev 379)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-05-09 22:27:43 UTC (rev 380)
@@ -163,12 +163,6 @@
amax(DTOR(20.0)),
tf(NULL)
{
- advertise<MsgPlanner2DState>("state");
- advertise<MsgRobotBase2DCmdVel>("cmdvel");
- subscribe("goal", goalMsg, &WavefrontNode::goalReceived);
- subscribe("odom", odomMsg, &WavefrontNode::odomReceived);
- subscribe("scan", laserMsg, &WavefrontNode::laserReceived);
-
// TODO: get map via RPC
char* mapdata;
int sx, sy;
@@ -209,6 +203,12 @@
plan_compute_cspace(this->plan);
this->tf = new rosTFClient(*this);
+
+ advertise<MsgPlanner2DState>("state");
+ advertise<MsgRobotBase2DCmdVel>("cmdvel");
+ subscribe("goal", goalMsg, &WavefrontNode::goalReceived);
+ subscribe("odom", odomMsg, &WavefrontNode::odomReceived);
+ subscribe("scan", laserMsg, &WavefrontNode::laserReceived);
}
WavefrontNode::~WavefrontNode()
@@ -243,11 +243,19 @@
odomMsg.header.stamp_nsecs;
odom_pose.frame = odomMsg.header.frame_id;
- libTF::TFPose2D global_pose = this->tf->transformPose2D(this->tf->ROOT_FRAME,
- odom_pose);
- this->pose[0] = global_pose.x;
- this->pose[1] = global_pose.y;
- this->pose[2] = global_pose.yaw;
+ printf("frame: %d\n", odomMsg.header.frame_id);
+ try
+ {
+ libTF::TFPose2D global_pose =
+ this->tf->transformPose2D(1, odom_pose);
+ this->pose[0] = global_pose.x;
+ this->pose[1] = global_pose.y;
+ this->pose[2] = global_pose.yaw;
+ }
+ catch(libTF::TransformReference::LookupException& ex)
+ {
+ puts("no tx yet");
+ }
}
void
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mor...@us...> - 2008-05-11 08:03:44
|
Revision: 383
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=383&view=rev
Author: morgan_quigley
Date: 2008-05-11 00:56:20 -0700 (Sun, 11 May 2008)
Log Message:
-----------
beginnings of a package to wrap the opencv calibration. it's trivial right now, but it at least shows how to link against the handy opencv ROS package
Added Paths:
-----------
pkg/trunk/vision/
pkg/trunk/vision/cv_cam_calib/
pkg/trunk/vision/cv_cam_calib/Makefile
pkg/trunk/vision/cv_cam_calib/cv_cam_calib.cpp
pkg/trunk/vision/cv_cam_calib/manifest.xml
Added: pkg/trunk/vision/cv_cam_calib/Makefile
===================================================================
--- pkg/trunk/vision/cv_cam_calib/Makefile (rev 0)
+++ pkg/trunk/vision/cv_cam_calib/Makefile 2008-05-11 07:56:20 UTC (rev 383)
@@ -0,0 +1,4 @@
+SRC = cv_cam_calib.cpp
+OUT = cv_cam_calib
+PKG = cv_cam_calib
+include $(shell rospack find mk)/node.mk
Added: pkg/trunk/vision/cv_cam_calib/cv_cam_calib.cpp
===================================================================
--- pkg/trunk/vision/cv_cam_calib/cv_cam_calib.cpp (rev 0)
+++ pkg/trunk/vision/cv_cam_calib/cv_cam_calib.cpp 2008-05-11 07:56:20 UTC (rev 383)
@@ -0,0 +1,43 @@
+#include <cstdio>
+#include "opencv/cv.h"
+#include "opencv/highgui.h"
+
+int main(int argc, char **argv)
+{
+ if (argc <= 1)
+ {
+ printf("usage: cv_cam_calib IMG1 IMG2 IMG3 ...\n");
+ return 1;
+ }
+ for (int i = 1; i < 2; i++) //argc; i++)
+ {
+ IplImage *img = cvLoadImage(argv[i]);
+ if (!img)
+ {
+ printf("couldn't load image\n");
+ return 1;
+ }
+ cvNamedWindow("checkers", CV_WINDOW_AUTOSIZE);
+ const int horiz_corners = 6, vert_corners = 7;
+ const int num_corners = horiz_corners * vert_corners;
+ CvSize pattern_size = cvSize(horiz_corners, vert_corners);
+ CvPoint2D32f corners[num_corners];
+ int corner_count;
+ int ok = cvFindChessboardCorners(img, pattern_size,
+ corners, &corner_count, 0);
+ cvDrawChessboardCorners(img, pattern_size, corners, corner_count, ok);
+ cvShowImage("checkers", img);
+/*
+ if (corner_count == num_corners)
+ {
+ printf("found all %d corners\n", corner_count);
+ }
+ else
+ printf("couldn't find all corners\n");
+*/
+ cvWaitKey(0);
+ cvReleaseImage(&img);
+ }
+ return 0;
+}
+
Added: pkg/trunk/vision/cv_cam_calib/manifest.xml
===================================================================
--- pkg/trunk/vision/cv_cam_calib/manifest.xml (rev 0)
+++ pkg/trunk/vision/cv_cam_calib/manifest.xml 2008-05-11 07:56:20 UTC (rev 383)
@@ -0,0 +1,10 @@
+<package>
+ <description>
+ A wrapper for the OpenCV image calibration code. Just give a bunch of image
+ files as arguments to this executable, and it will try to use the OpenCV
+ automatic calibration routines to estimate the camera intrinsics.
+ </description>
+ <author>Morgan Quigley</author>
+ <license>BSD</license>
+ <depend package="opencv"/>
+</package>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-05-12 18:28:01
|
Revision: 398
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=398&view=rev
Author: gerkey
Date: 2008-05-12 11:26:25 -0700 (Mon, 12 May 2008)
Log Message:
-----------
added license statements
Modified Paths:
--------------
pkg/trunk/3rdparty/player/manifest.xml
pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc
pkg/trunk/nav/amcl_player/Makefile
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/teleop_base_keyboard/teleop_base_keyboard.cc
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/simulators/rosstage/rosstage.cc
Modified: pkg/trunk/3rdparty/player/manifest.xml
===================================================================
--- pkg/trunk/3rdparty/player/manifest.xml 2008-05-12 16:56:50 UTC (rev 397)
+++ pkg/trunk/3rdparty/player/manifest.xml 2008-05-12 18:26:25 UTC (rev 398)
@@ -12,7 +12,7 @@
<license>LGPL</license>
<url>http://playerstage.sf.net</url>
<export>
- <cpp lflags="-Xlinker -rpath ${prefix}/player/lib -L${prefix}/player/lib -lplayerdrivers -lplayercore -lplayerxdr -lplayerutils -lplayererror" cflags="-I${prefix}/player/include/player-2.2"/>
+ <cpp lflags="-Xlinker -rpath ${prefix}/player/lib -L${prefix}/player/lib -lplayercore -lplayerxdr -lplayerutils -lplayererror" cflags="-I${prefix}/player/include/player-2.2"/>
</export>
</package>
Modified: pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc
===================================================================
--- pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc 2008-05-12 16:56:50 UTC (rev 397)
+++ pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc 2008-05-12 18:26:25 UTC (rev 398)
@@ -1,4 +1,24 @@
#include <assert.h>
+/*
+ * Software License Agreement (GNU LGPL)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
#include <libstandalone_drivers/urg_laser.h>
Modified: pkg/trunk/nav/amcl_player/Makefile
===================================================================
--- pkg/trunk/nav/amcl_player/Makefile 2008-05-12 16:56:50 UTC (rev 397)
+++ pkg/trunk/nav/amcl_player/Makefile 2008-05-12 18:26:25 UTC (rev 398)
@@ -3,7 +3,7 @@
all: $(PKG)
CFLAGS = -g -Wall `rospack export/cpp/cflags $(PKG)` `pkg-config --cflags gdk-pixbuf-2.0`
-LFLAGS = `rospack export/cpp/lflags $(PKG)` `pkg-config --libs gdk-pixbuf-2.0`
+LFLAGS = `rospack export/cpp/lflags $(PKG)` -lplayerdrivers `pkg-config --libs gdk-pixbuf-2.0`
amcl_player: amcl_player.cc
$(CXX) $(CFLAGS) -o $@ $< $(LFLAGS)
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2008-05-12 16:56:50 UTC (rev 397)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2008-05-12 18:26:25 UTC (rev 398)
@@ -1,3 +1,24 @@
+/*
+ * Software License Agreement (GNU LGPL)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+
#include <assert.h>
// For core Player stuff (message queues, config file objects, etc.)
@@ -54,6 +75,7 @@
ConfigFile* cf;
// incoming messages
+ MsgRobotBase2DOdom localizedOdomMsg;
MsgRobotBase2DOdom odomMsg;
MsgLaserScan laserMsg;
@@ -126,6 +148,7 @@
// TODO: remove XDR dependency
playerxdr_ftable_init();
+ advertise<MsgRobotBase2DOdom>("localizedpose");
subscribe("odom", odomMsg, &AmclNode::odomReceived);
subscribe("scan", laserMsg, &AmclNode::laserReceived);
@@ -251,6 +274,7 @@
odomMsg.pos.x,
odomMsg.pos.y,
RTOD(odomMsg.pos.th));
+ /*
this->tf->sendEuler(2,1,
this->odomMsg.pos.x-pdata->pos.px,
this->odomMsg.pos.y-pdata->pos.py,
@@ -269,6 +293,15 @@
(long long unsigned int)floor(hdr->timestamp),
(long long unsigned int)((hdr->timestamp - floor(hdr->timestamp)) *
1000000000ULL));
+ */
+ printf("pose: (%.3f %.3f %.3f)\n",
+ pdata->pos.px,
+ pdata->pos.py,
+ RTOD(pdata->pos.pa));
+ localizedOdomMsg.pos.x = pdata->pos.px;
+ localizedOdomMsg.pos.y = pdata->pos.py;
+ localizedOdomMsg.pos.th = pdata->pos.pa;
+ publish("localizedpose", localizedOdomMsg);
return(0);
}
@@ -408,7 +441,7 @@
if(!this->Driver::InQueue->Empty())
this->Driver::ProcessMessages();
else
- usleep(1000000);
+ usleep(100000);
return(0);
}
Modified: pkg/trunk/nav/teleop_base_keyboard/teleop_base_keyboard.cc
===================================================================
--- pkg/trunk/nav/teleop_base_keyboard/teleop_base_keyboard.cc 2008-05-12 16:56:50 UTC (rev 397)
+++ pkg/trunk/nav/teleop_base_keyboard/teleop_base_keyboard.cc 2008-05-12 18:26:25 UTC (rev 398)
@@ -1,3 +1,35 @@
+//Software License Agreement (BSD License)
+
+//Copyright (c) 2008, Willow Garage, Inc.
+//All rights reserved.
+
+//Redistribution and use in source and binary forms, with or without
+//modification, are permitted provided that the following conditions
+//are met:
+
+// * Redistributions of source code must retain the above copyright
+// notice, this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above
+// copyright notice, this list of conditions and the following
+// disclaimer in the documentation and/or other materials provided
+// with the distribution.
+// * Neither the name of the Willow Garage nor the names of its
+// contributors may be used to endorse or promote products derived
+// from this software without specific prior written permission.
+
+//THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+//"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+//LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+//FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+//COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+//INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+//BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+//LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+//CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+//LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+//ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+//POSSIBILITY OF SUCH DAMAGE.
+
#include <termios.h>
#include <signal.h>
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-05-12 16:56:50 UTC (rev 397)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-05-12 18:26:25 UTC (rev 398)
@@ -1,3 +1,24 @@
+/*
+ * Software License Agreement (GNU LGPL)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+
#include <stdio.h>
#include <assert.h>
#include <stdlib.h>
@@ -13,14 +34,14 @@
// The messages that we'll use
#include <std_msgs/MsgPlanner2DState.h>
#include <std_msgs/MsgPlanner2DGoal.h>
-#include <std_msgs/MsgRobotBase2DCmdVel.h>
+#include <std_msgs/MsgBaseVel.h>
#include <std_msgs/MsgRobotBase2DOdom.h>
#include <std_msgs/MsgLaserScan.h>
// For transform support
#include <rosTF/rosTF.h>
-#define ANG_NORM(a) atan2(cos((a)),sin((a)))
+#define ANG_NORM(a) atan2(sin((a)),cos((a)))
#define DTOR(a) ((a)*M_PI/180.0)
#define RTOD(a) ((a)*180.0/M_PI)
#define SIGN(x) (((x) < 0.0) ? -1 : 1)
@@ -44,7 +65,6 @@
{
NO_GOAL,
PURSUING_GOAL,
- ROTATING_AT_GOAL,
REACHED_GOAL
} planner_state;
// Are we enabled?
@@ -145,7 +165,7 @@
rotate_dir(0),
printed_warning(false),
stopped(false),
- robot_radius(0.16),
+ robot_radius(0.2),
safety_dist(0.05),
max_radius(0.25),
dist_penalty(1.0),
@@ -158,9 +178,9 @@
lookahead_maxdist(2.0),
lookahead_distweight(10.0),
tvmin(0.1),
- tvmax(0.5),
+ tvmax(0.35),
avmin(DTOR(10.0)),
- avmax(DTOR(90.0)),
+ avmax(DTOR(60.0)),
amin(DTOR(5.0)),
amax(DTOR(20.0)),
tf(NULL)
@@ -186,8 +206,12 @@
{
for(int i=0;i<sx;i++)
{
- this->plan->cells[i+j*sx].occ_state =
- mapdata[MAP_IDX(sx,i,j)];
+ if(mapdata[i+j*sx] < 0.1*255)
+ this->plan->cells[i+j*sx].occ_state = -1;
+ else if(mapdata[i+j*sx] > 0.9*255)
+ this->plan->cells[i+j*sx].occ_state = 1;
+ else
+ this->plan->cells[i+j*sx].occ_state = 0;
}
}
free(mapdata);
@@ -207,9 +231,10 @@
this->tf = new rosTFClient(*this);
advertise<MsgPlanner2DState>("state");
- advertise<MsgRobotBase2DCmdVel>("cmdvel");
+ advertise<MsgBaseVel>("cmd_vel");
subscribe("goal", goalMsg, &WavefrontNode::goalReceived);
- subscribe("odom", odomMsg, &WavefrontNode::odomReceived);
+ //subscribe("odom", odomMsg, &WavefrontNode::odomReceived);
+ subscribe("localizedpose", odomMsg, &WavefrontNode::odomReceived);
subscribe("scan", laserMsg, &WavefrontNode::laserReceived);
}
@@ -226,6 +251,11 @@
this->lock.lock();
// Got a new goal message; handle it
this->enable = goalMsg.enable;
+ printf("got new goal: %.3f %.3f %.3f\n",
+ goalMsg.goal.x,
+ goalMsg.goal.y,
+ RTOD(goalMsg.goal.th));
+
if(this->enable)
{
this->goal[0] = goalMsg.goal.x;
@@ -240,6 +270,7 @@
WavefrontNode::odomReceived()
{
this->lock.lock();
+ /*
libTF::TFPose2D odom_pose;
odom_pose.x = odomMsg.pos.x;
odom_pose.y = odomMsg.pos.y;
@@ -270,6 +301,14 @@
{
puts("no global->local Tx yet");
}
+ */
+ this->pose[0] = odomMsg.pos.x;
+ this->pose[1] = odomMsg.pos.y;
+ this->pose[2] = odomMsg.pos.th;
+ printf("gpose: %.3f %.3f %.3f\n",
+ this->pose[0],
+ this->pose[1],
+ RTOD(this->pose[2]));
this->lock.unlock();
}
@@ -283,27 +322,26 @@
void
WavefrontNode::stopRobot()
{
- if(!this->stopped)
- {
+ //if(!this->stopped)
+ //{
// TODO: should we send more than once, or perhaps use RPC for this?
this->sendVelCmd(0.0,0.0,0.0);
this->stopped = true;
- }
+ //}
}
// Declare this globally, so that it never gets desctructed (message
// desctruction causes master disconnect)
-MsgRobotBase2DCmdVel* cmdvel;
+MsgBaseVel* cmdvel;
void
WavefrontNode::sendVelCmd(double vx, double vy, double vth)
{
if(!cmdvel)
- cmdvel = new MsgRobotBase2DCmdVel();
- cmdvel->vel.x = vx;
- cmdvel->vel.y = vy;
- cmdvel->vel.th = vth;
- this->ros::node::publish("cmdvel", *cmdvel);
+ cmdvel = new MsgBaseVel();
+ cmdvel->vx = vx;
+ cmdvel->vw = vth;
+ this->ros::node::publish("cmd_vel", *cmdvel);
}
@@ -320,14 +358,14 @@
this->lock.lock();
switch(this->planner_state)
{
- // Treat these states the same; do nothing
case NO_GOAL:
+ puts("no goal");
+ this->stopRobot();
+ break;
case REACHED_GOAL:
+ puts("still done");
this->stopRobot();
break;
- case ROTATING_AT_GOAL:
-
- break;
case PURSUING_GOAL:
{
// Are we done?
@@ -336,6 +374,7 @@
this->goal[0], this->goal[1], this->goal[2],
this->dist_eps, this->ang_eps))
{
+ puts("done");
this->stopRobot();
this->planner_state = REACHED_GOAL;
break;
@@ -352,11 +391,11 @@
// no global plan
this->stopRobot();
- if(!this->printed_warning)
- {
+ //if(!this->printed_warning)
+ //{
puts("global plan failed");
- this->printed_warning = true;
- }
+ //this->printed_warning = true;
+ //}
break;
}
else
@@ -393,6 +432,7 @@
break;
}
+ printf("computed velocities: %.3f %.3f\n", vx, RTOD(va));
this->sendVelCmd(vx, 0.0, va);
break;
Modified: pkg/trunk/simulators/rosstage/rosstage.cc
===================================================================
--- pkg/trunk/simulators/rosstage/rosstage.cc 2008-05-12 16:56:50 UTC (rev 397)
+++ pkg/trunk/simulators/rosstage/rosstage.cc 2008-05-12 18:26:25 UTC (rev 398)
@@ -1,3 +1,24 @@
+/*
+ * Software License Agreement (GNU GPL)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -13,26 +34,46 @@
#define USAGE "rosstage <worldfile>"
+// Our node
class StageNode : public ros::node
{
private:
+ // Messages that we'll send or receive
MsgBaseVel velMsg;
MsgLaserScan laserMsg;
MsgRobotBase2DOdom odomMsg;
+
+ // A mutex to lock access to fields that are used in message callbacks
ros::thread::mutex lock;
+ // The models that we're interested in
+ Stg::StgModelLaser* lasermodel;
+ Stg::StgModelPosition* positionmodel;
+
+ // A helper function that is executed for each stage model. We use it
+ // to search for models of interest.
+ static void ghfunc(gpointer key, Stg::StgModel* mod, StageNode* node);
+
public:
+ // Constructor; stage itself needs argc/argv. fname is the .world file
+ // that stage should load.
StageNode(int argc, char** argv, const char* fname);
~StageNode();
+
+ // Subscribe to models of interest. Currently, we find and subscribe
+ // to the first 'laser' model and the first 'position' model. Returns
+ // 0 on success (both models subscribed), -1 otherwise.
int SubscribeModels();
- void cmdvelReceived();
+
+ // Do one update of the simulator. May pause if the next update time
+ // has not yet arrived.
void Update();
- static void ghfunc(gpointer key, Stg::StgModel* mod, StageNode* node);
+ // Message callback for a MsgBaseVel message, which set velocities.
+ void cmdvelReceived();
+ // The main simulator object
Stg::StgWorldGui* world;
- Stg::StgModelLaser* lasermodel;
- Stg::StgModelPosition* positionmodel;
};
void
@@ -80,6 +121,12 @@
this->world->ForEachModel((GHFunc)ghfunc, this);
}
+// Subscribe to models of interest. Currently, we find and subscribe
+// to the first 'laser' model and the first 'position' model. Returns
+// 0 on success (both models subscribed), -1 otherwise.
+//
+// Eventually, we should provide a general way to map stage models onto ROS
+// topics, similar to Player .cfg files.
int
StageNode::SubscribeModels()
{
@@ -111,13 +158,18 @@
void
StageNode::Update()
{
+ // Wait until it's time to update
this->world->PauseUntilNextUpdateTime();
this->lock.lock();
+
+ // Let the simulator update
this->world->Update();
+ // Get latest laser data
Stg::stg_laser_sample_t* samples = this->lasermodel->GetSamples();
if(samples)
{
+ // Translate into ROS message format and publish
Stg::stg_laser_cfg_t cfg = this->lasermodel->GetConfig();
this->laserMsg.angle_min = -cfg.fov/2.0;
this->laserMsg.angle_max = +cfg.fov/2.0;
@@ -134,20 +186,20 @@
publish("scan",this->laserMsg);
}
+ // Get latest odometry data
+ // Translate into ROS message format and publish
this->odomMsg.pos.x = this->positionmodel->est_pose.x;
this->odomMsg.pos.y = this->positionmodel->est_pose.y;
this->odomMsg.pos.th = this->positionmodel->est_pose.a;
-
Stg::stg_velocity_t v = this->positionmodel->GetVelocity();
-
this->odomMsg.vel.x = v.x;
this->odomMsg.vel.y = v.y;
this->odomMsg.vel.th = v.a;
-
this->odomMsg.stall = this->positionmodel->Stall();
+ // TODO: get the frame ID from somewhere
+ this->odomMsg.header.frame_id = 2;
publish("odom",this->odomMsg);
- puts("published");
this->lock.unlock();
}
@@ -174,7 +226,7 @@
}
// have to call this explicitly for some reason. probably interference
- // from signal handling in Stage?
+ // from signal handling in Stage / FLTK?
ros::msg_destruct();
exit(0);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-05-14 20:54:41
|
Revision: 413
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=413&view=rev
Author: gerkey
Date: 2008-05-14 13:54:48 -0700 (Wed, 14 May 2008)
Log Message:
-----------
added LICENSE directory
Modified Paths:
--------------
pkg/trunk/drivers/robot/erratic_player/erratic_player.cc
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/amcl_player/manifest.xml
pkg/trunk/nav/teleop_base_keyboard/teleop_base_keyboard.cc
pkg/trunk/nav/wavefront_player/manifest.xml
pkg/trunk/nav/wavefront_player/wavefront_player.cc
Added Paths:
-----------
pkg/trunk/LICENSE/
pkg/trunk/LICENSE/BSD-summary.c
pkg/trunk/LICENSE/BSD.txt
pkg/trunk/LICENSE/GPL-summary.c
pkg/trunk/LICENSE/GPL.txt
pkg/trunk/LICENSE/LGPL-summary.c
pkg/trunk/LICENSE/LGPL.txt
pkg/trunk/LICENSE/README
Added: pkg/trunk/LICENSE/BSD-summary.c
===================================================================
--- pkg/trunk/LICENSE/BSD-summary.c (rev 0)
+++ pkg/trunk/LICENSE/BSD-summary.c 2008-05-14 20:54:48 UTC (rev 413)
@@ -0,0 +1,30 @@
+/*
+ * <PACKAGE_NAME>
+ * Copyright (c) <YEAR>, <OWNER>
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * * Neither the name of the <ORGANIZATION> nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
Added: pkg/trunk/LICENSE/BSD.txt
===================================================================
--- pkg/trunk/LICENSE/BSD.txt (rev 0)
+++ pkg/trunk/LICENSE/BSD.txt 2008-05-14 20:54:48 UTC (rev 413)
@@ -0,0 +1,26 @@
+Copyright (c) <YEAR>, <OWNER>
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of the <ORGANIZATION> nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGE.
Added: pkg/trunk/LICENSE/GPL-summary.c
===================================================================
--- pkg/trunk/LICENSE/GPL-summary.c (rev 0)
+++ pkg/trunk/LICENSE/GPL-summary.c 2008-05-14 20:54:48 UTC (rev 413)
@@ -0,0 +1,19 @@
+/*
+ * <PACKAGE_NAME>
+ * Copyright (c) <YEAR>, <OWNER>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+
Added: pkg/trunk/LICENSE/GPL.txt
===================================================================
--- pkg/trunk/LICENSE/GPL.txt (rev 0)
+++ pkg/trunk/LICENSE/GPL.txt 2008-05-14 20:54:48 UTC (rev 413)
@@ -0,0 +1,339 @@
+ GNU GENERAL PUBLIC LICENSE
+ Version 2, June 1991
+
+ Copyright (C) 1989, 1991 Free Software Foundation, Inc.,
+ 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
+ Everyone is permitted to copy and distribute verbatim copies
+ of this license document, but changing it is not allowed.
+
+ Preamble
+
+ The licenses for most software are designed to take away your
+freedom to share and change it. By contrast, the GNU General Public
+License is intended to guarantee your freedom to share and change free
+software--to make sure the software is free for all its users. This
+General Public License applies to most of the Free Software
+Foundation's software and to any other program whose authors commit to
+using it. (Some other Free Software Foundation software is covered by
+the GNU Lesser General Public License instead.) You can apply it to
+your programs, too.
+
+ When we speak of free software, we are referring to freedom, not
+price. Our General Public Licenses are designed to make sure that you
+have the freedom to distribute copies of free software (and charge for
+this service if you wish), that you receive source code or can get it
+if you want it, that you can change the software or use pieces of it
+in new free programs; and that you know you can do these things.
+
+ To protect your rights, we need to make restrictions that forbid
+anyone to deny you these rights or to ask you to surrender the rights.
+These restrictions translate to certain responsibilities for you if you
+distribute copies of the software, or if you modify it.
+
+ For example, if you distribute copies of such a program, whether
+gratis or for a fee, you must give the recipients all the rights that
+you have. You must make sure that they, too, receive or can get the
+source code. And you must show them these terms so they know their
+rights.
+
+ We protect your rights with two steps: (1) copyright the software, and
+(2) offer you this license which gives you legal permission to copy,
+distribute and/or modify the software.
+
+ Also, for each author's protection and ours, we want to make certain
+that everyone understands that there is no warranty for this free
+software. If the software is modified by someone else and passed on, we
+want its recipients to know that what they have is not the original, so
+that any problems introduced by others will not reflect on the original
+authors' reputations.
+
+ Finally, any free program is threatened constantly by software
+patents. We wish to avoid the danger that redistributors of a free
+program will individually obtain patent licenses, in effect making the
+program proprietary. To prevent this, we have made it clear that any
+patent must be licensed for everyone's free use or not licensed at all.
+
+ The precise terms and conditions for copying, distribution and
+modification follow.
+
+ GNU GENERAL PUBLIC LICENSE
+ TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
+
+ 0. This License applies to any program or other work which contains
+a notice placed by the copyright holder saying it may be distributed
+under the terms of this General Public License. The "Program", below,
+refers to any such program or work, and a "work based on the Program"
+means either the Program or any derivative work under copyright law:
+that is to say, a work containing the Program or a portion of it,
+either verbatim or with modifications and/or translated into another
+language. (Hereinafter, translation is included without limitation in
+the term "modification".) Each licensee is addressed as "you".
+
+Activities other than copying, distribution and modification are not
+covered by this License; they are outside its scope. The act of
+running the Program is not restricted, and the output from the Program
+is covered only if its contents constitute a work based on the
+Program (independent of having been made by running the Program).
+Whether that is true depends on what the Program does.
+
+ 1. You may copy and distribute verbatim copies of the Program's
+source code as you receive it, in any medium, provided that you
+conspicuously and appropriately publish on each copy an appropriate
+copyright notice and disclaimer of warranty; keep intact all the
+notices that refer to this License and to the absence of any warranty;
+and give any other recipients of the Program a copy of this License
+along with the Program.
+
+You may charge a fee for the physical act of transferring a copy, and
+you may at your option offer warranty protection in exchange for a fee.
+
+ 2. You may modify your copy or copies of the Program or any portion
+of it, thus forming a work based on the Program, and copy and
+distribute such modifications or work under the terms of Section 1
+above, provided that you also meet all of these conditions:
+
+ a) You must cause the modified files to carry prominent notices
+ stating that you changed the files and the date of any change.
+
+ b) You must cause any work that you distribute or publish, that in
+ whole or in part contains or is derived from the Program or any
+ part thereof, to be licensed as a whole at no charge to all third
+ parties under the terms of this License.
+
+ c) If the modified program normally reads commands interactively
+ when run, you must cause it, when started running for such
+ interactive use in the most ordinary way, to print or display an
+ announcement including an appropriate copyright notice and a
+ notice that there is no warranty (or else, saying that you provide
+ a warranty) and that users may redistribute the program under
+ these conditions, and telling the user how to view a copy of this
+ License. (Exception: if the Program itself is interactive but
+ does not normally print such an announcement, your work based on
+ the Program is not required to print an announcement.)
+
+These requirements apply to the modified work as a whole. If
+identifiable sections of that work are not derived from the Program,
+and can be reasonably considered independent and separate works in
+themselves, then this License, and its terms, do not apply to those
+sections when you distribute them as separate works. But when you
+distribute the same sections as part of a whole which is a work based
+on the Program, the distribution of the whole must be on the terms of
+this License, whose permissions for other licensees extend to the
+entire whole, and thus to each and every part regardless of who wrote it.
+
+Thus, it is not the intent of this section to claim rights or contest
+your rights to work written entirely by you; rather, the intent is to
+exercise the right to control the distribution of derivative or
+collective works based on the Program.
+
+In addition, mere aggregation of another work not based on the Program
+with the Program (or with a work based on the Program) on a volume of
+a storage or distribution medium does not bring the other work under
+the scope of this License.
+
+ 3. You may copy and distribute the Program (or a work based on it,
+under Section 2) in object code or executable form under the terms of
+Sections 1 and 2 above provided that you also do one of the following:
+
+ a) Accompany it with the complete corresponding machine-readable
+ source code, which must be distributed under the terms of Sections
+ 1 and 2 above on a medium customarily used for software interchange; or,
+
+ b) Accompany it with a written offer, valid for at least three
+ years, to give any third party, for a charge no more than your
+ cost of physically performing source distribution, a complete
+ machine-readable copy of the corresponding source code, to be
+ distributed under the terms of Sections 1 and 2 above on a medium
+ customarily used for software interchange; or,
+
+ c) Accompany it with the information you received as to the offer
+ to distribute corresponding source code. (This alternative is
+ allowed only for noncommercial distribution and only if you
+ received the program in object code or executable form with such
+ an offer, in accord with Subsection b above.)
+
+The source code for a work means the preferred form of the work for
+making modifications to it. For an executable work, complete source
+code means all the source code for all modules it contains, plus any
+associated interface definition files, plus the scripts used to
+control compilation and installation of the executable. However, as a
+special exception, the source code distributed need not include
+anything that is normally distributed (in either source or binary
+form) with the major components (compiler, kernel, and so on) of the
+operating system on which the executable runs, unless that component
+itself accompanies the executable.
+
+If distribution of executable or object code is made by offering
+access to copy from a designated place, then offering equivalent
+access to copy the source code from the same place counts as
+distribution of the source code, even though third parties are not
+compelled to copy the source along with the object code.
+
+ 4. You may not copy, modify, sublicense, or distribute the Program
+except as expressly provided under this License. Any attempt
+otherwise to copy, modify, sublicense or distribute the Program is
+void, and will automatically terminate your rights under this License.
+However, parties who have received copies, or rights, from you under
+this License will not have their licenses terminated so long as such
+parties remain in full compliance.
+
+ 5. You are not required to accept this License, since you have not
+signed it. However, nothing else grants you permission to modify or
+distribute the Program or its derivative works. These actions are
+prohibited by law if you do not accept this License. Therefore, by
+modifying or distributing the Program (or any work based on the
+Program), you indicate your acceptance of this License to do so, and
+all its terms and conditions for copying, distributing or modifying
+the Program or works based on it.
+
+ 6. Each time you redistribute the Program (or any work based on the
+Program), the recipient automatically receives a license from the
+original licensor to copy, distribute or modify the Program subject to
+these terms and conditions. You may not impose any further
+restrictions on the recipients' exercise of the rights granted herein.
+You are not responsible for enforcing compliance by third parties to
+this License.
+
+ 7. If, as a consequence of a court judgment or allegation of patent
+infringement or for any other reason (not limited to patent issues),
+conditions are imposed on you (whether by court order, agreement or
+otherwise) that contradict the conditions of this License, they do not
+excuse you from the conditions of this License. If you cannot
+distribute so as to satisfy simultaneously your obligations under this
+License and any other pertinent obligations, then as a consequence you
+may not distribute the Program at all. For example, if a patent
+license would not permit royalty-free redistribution of the Program by
+all those who receive copies directly or indirectly through you, then
+the only way you could satisfy both it and this License would be to
+refrain entirely from distribution of the Program.
+
+If any portion of this section is held invalid or unenforceable under
+any particular circumstance, the balance of the section is intended to
+apply and the section as a whole is intended to apply in other
+circumstances.
+
+It is not the purpose of this section to induce you to infringe any
+patents or other property right claims or to contest validity of any
+such claims; this section has the sole purpose of protecting the
+integrity of the free software distribution system, which is
+implemented by public license practices. Many people have made
+generous contributions to the wide range of software distributed
+through that system in reliance on consistent application of that
+system; it is up to the author/donor to decide if he or she is willing
+to distribute software through any other system and a licensee cannot
+impose that choice.
+
+This section is intended to make thoroughly clear what is believed to
+be a consequence of the rest of this License.
+
+ 8. If the distribution and/or use of the Program is restricted in
+certain countries either by patents or by copyrighted interfaces, the
+original copyright holder who places the Program under this License
+may add an explicit geographical distribution limitation excluding
+those countries, so that distribution is permitted only in or among
+countries not thus excluded. In such case, this License incorporates
+the limitation as if written in the body of this License.
+
+ 9. The Free Software Foundation may publish revised and/or new versions
+of the General Public License from time to time. Such new versions will
+be similar in spirit to the present version, but may differ in detail to
+address new problems or concerns.
+
+Each version is given a distinguishing version number. If the Program
+specifies a version number of this License which applies to it and "any
+later version", you have the option of following the terms and conditions
+either of that version or of any later version published by the Free
+Software Foundation. If the Program does not specify a version number of
+this License, you may choose any version ever published by the Free Software
+Foundation.
+
+ 10. If you wish to incorporate parts of the Program into other free
+programs whose distribution conditions are different, write to the author
+to ask for permission. For software which is copyrighted by the Free
+Software Foundation, write to the Free Software Foundation; we sometimes
+make exceptions for this. Our decision will be guided by the two goals
+of preserving the free status of all derivatives of our free software and
+of promoting the sharing and reuse of software generally.
+
+ NO WARRANTY
+
+ 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY
+FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN
+OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES
+PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED
+OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS
+TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE
+PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING,
+REPAIR OR CORRECTION.
+
+ 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
+WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR
+REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES,
+INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING
+OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED
+TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY
+YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER
+PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGES.
+
+ END OF TERMS AND CONDITIONS
+
+ How to Apply These Terms to Your New Programs
+
+ If you develop a new program, and you want it to be of the greatest
+possible use to the public, the best way to achieve this is to make it
+free software which everyone can redistribute and change under these terms.
+
+ To do so, attach the following notices to the program. It is safest
+to attach them to the start of each source file to most effectively
+convey the exclusion of warranty; and each file should have at least
+the "copyright" line and a pointer to where the full notice is found.
+
+ <one line to give the program's name and a brief idea of what it does.>
+ Copyright (C) <year> <name of author>
+
+ This program is free software; you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation; either version 2 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License along
+ with this program; if not, write to the Free Software Foundation, Inc.,
+ 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+
+Also add information on how to contact you by electronic and paper mail.
+
+If the program is interactive, make it output a short notice like this
+when it starts in an interactive mode:
+
+ Gnomovision version 69, Copyright (C) year name of author
+ Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
+ This is free software, and you are welcome to redistribute it
+ under certain conditions; type `show c' for details.
+
+The hypothetical commands `show w' and `show c' should show the appropriate
+parts of the General Public License. Of course, the commands you use may
+be called something other than `show w' and `show c'; they could even be
+mouse-clicks or menu items--whatever suits your program.
+
+You should also get your employer (if you work as a programmer) or your
+school, if any, to sign a "copyright disclaimer" for the program, if
+necessary. Here is a sample; alter the names:
+
+ Yoyodyne, Inc., hereby disclaims all copyright interest in the program
+ `Gnomovision' (which makes passes at compilers) written by James Hacker.
+
+ <signature of Ty Coon>, 1 April 1989
+ Ty Coon, President of Vice
+
+This General Public License does not permit incorporating your program into
+proprietary programs. If your program is a subroutine library, you may
+consider it more useful to permit linking proprietary applications with the
+library. If this is what you want to do, use the GNU Lesser General
+Public License instead of this License.
Added: pkg/trunk/LICENSE/LGPL-summary.c
===================================================================
--- pkg/trunk/LICENSE/LGPL-summary.c (rev 0)
+++ pkg/trunk/LICENSE/LGPL-summary.c 2008-05-14 20:54:48 UTC (rev 413)
@@ -0,0 +1,21 @@
+/*
+ * <PACKAGE_NAME>
+ * Copyright (c) <YEAR>, <OWNER>
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Library General Public
+ * License as published by the Free Software Foundation; either
+ * version 2 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Library General Public License for more details.
+ *
+ * You should have received a copy of the GNU Library General Public
+ * License along with this library; if not, write to the
+ * Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
+ * Boston, MA 02110-1301, USA.
+ */
+
+
Added: pkg/trunk/LICENSE/LGPL.txt
===================================================================
--- pkg/trunk/LICENSE/LGPL.txt (rev 0)
+++ pkg/trunk/LICENSE/LGPL.txt 2008-05-14 20:54:48 UTC (rev 413)
@@ -0,0 +1,481 @@
+ GNU LIBRARY GENERAL PUBLIC LICENSE
+ Version 2, June 1991
+
+ Copyright (C) 1991 Free Software Foundation, Inc.
+ 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
+ Everyone is permitted to copy and distribute verbatim copies
+ of this license document, but changing it is not allowed.
+
+[This is the first released version of the library GPL. It is
+ numbered 2 because it goes with version 2 of the ordinary GPL.]
+
+ Preamble
+
+ The licenses for most software are designed to take away your
+freedom to share and change it. By contrast, the GNU General Public
+Licenses are intended to guarantee your freedom to share and change
+free software--to make sure the software is free for all its users.
+
+ This license, the Library General Public License, applies to some
+specially designated Free Software Foundation software, and to any
+other libraries whose authors decide to use it. You can use it for
+your libraries, too.
+
+ When we speak of free software, we are referring to freedom, not
+price. Our General Public Licenses are designed to make sure that you
+have the freedom to distribute copies of free software (and charge for
+this service if you wish), that you receive source code or can get it
+if you want it, that you can change the software or use pieces of it
+in new free programs; and that you know you can do these things.
+
+ To protect your rights, we need to make restrictions that forbid
+anyone to deny you these rights or to ask you to surrender the rights.
+These restrictions translate to certain responsibilities for you if
+you distribute copies of the library, or if you modify it.
+
+ For example, if you distribute copies of the library, whether gratis
+or for a fee, you must give the recipients all the rights that we gave
+you. You must make sure that they, too, receive or can get the source
+code. If you link a program with the library, you must provide
+complete object files to the recipients so that they can relink them
+with the library, after making changes to the library and recompiling
+it. And you must show them these terms so they know their rights.
+
+ Our method of protecting your rights has two steps: (1) copyright
+the library, and (2) offer you this license which gives you legal
+permission to copy, distribute and/or modify the library.
+
+ Also, for each distributor's protection, we want to make certain
+that everyone understands that there is no warranty for this free
+library. If the library is modified by someone else and passed on, we
+want its recipients to know that what they have is not the original
+version, so that any problems introduced by others will not reflect on
+the original authors' reputations.
+
+ Finally, any free program is threatened constantly by software
+patents. We wish to avoid the danger that companies distributing free
+software will individually obtain patent licenses, thus in effect
+transforming the program into proprietary software. To prevent this,
+we have made it clear that any patent must be licensed for everyone's
+free use or not licensed at all.
+
+ Most GNU software, including some libraries, is covered by the ordinary
+GNU General Public License, which was designed for utility programs. This
+license, the GNU Library General Public License, applies to certain
+designated libraries. This license is quite different from the ordinary
+one; be sure to read it in full, and don't assume that anything in it is
+the same as in the ordinary license.
+
+ The reason we have a separate public license for some libraries is that
+they blur the distinction we usually make between modifying or adding to a
+program and simply using it. Linking a program with a library, without
+changing the library, is in some sense simply using the library, and is
+analogous to running a utility program or application program. However, in
+a textual and legal sense, the linked executable is a combined work, a
+derivative of the original library, and the ordinary General Public License
+treats it as such.
+
+ Because of this blurred distinction, using the ordinary General
+Public License for libraries did not effectively promote software
+sharing, because most developers did not use the libraries. We
+concluded that weaker conditions might promote sharing better.
+
+ However, unrestricted linking of non-free programs would deprive the
+users of those programs of all benefit from the free status of the
+libraries themselves. This Library General Public License is intended to
+permit developers of non-free programs to use free libraries, while
+preserving your freedom as a user of such programs to change the free
+libraries that are incorporated in them. (We have not seen how to achieve
+this as regards changes in header files, but we...
[truncated message content] |