20 #include <webots_ros/sensor_set.h>    23 #include <webots_ros/set_float.h>    24 #include <webots_ros/set_int.h>    26 #include <std_msgs/Float64.h>    27 #include <std_msgs/Float64MultiArray.h>    28 #include <std_msgs/String.h>    31 #define ACCELERATION 10    33 #define ROTATE_SPEED 6   125 void imuCallback(
const std_msgs::Float64MultiArray::ConstPtr &values) {
   127   for (std::vector<double>::const_iterator it = values->data.begin(); it != values->data.end(); ++it) {
   272   ROS_INFO(
"User stopped the 'pr2_beer' node.");
   277 int main(
int argc, 
char **argv) {
   282   signal(SIGINT, 
quit);
   298     int wantedController = 0;
   299     std::cout << 
"Choose the # of the controller you want to use:\n";
   300     std::cin >> wantedController;
   304       ROS_ERROR(
"Invalid number for controller choice.");
   320   webots_ros::set_float fllWheelAccelerationSrv;
   321   webots_ros::set_float flrWheelAccelerationSrv;
   322   webots_ros::set_float frlWheelAccelerationSrv;
   323   webots_ros::set_float frrWheelAccelerationSrv;
   324   webots_ros::set_float bllWheelAccelerationSrv;
   325   webots_ros::set_float blrWheelAccelerationSrv;
   326   webots_ros::set_float brlWheelAccelerationSrv;
   327   webots_ros::set_float brrWheelAccelerationSrv;
   330   webots_ros::set_float headTiltSrv;
   332   webots_ros::set_float torsoSrv;
   334   webots_ros::set_float lShoulderRollSrv;
   336   webots_ros::set_float lShoulderLiftSrv;
   338   webots_ros::set_float rShoulderRollSrv;
   340   webots_ros::set_float rShoulderLiftSrv;
   342   webots_ros::set_float ruArmRollSrv;
   344   webots_ros::set_float rElbowLiftSrv;
   346   webots_ros::set_float lElbowLiftSrv;
   348   webots_ros::set_float rWristRollSrv;
   350   webots_ros::set_float llFingerSrv;
   352   webots_ros::set_float lrFingerSrv;
   354   webots_ros::set_float lrFingerTipSrv;
   356   webots_ros::set_float llFingerTipSrv;
   358   webots_ros::set_float rlFingerSrv;
   360   webots_ros::set_float rrFingerSrv;
   363   webots_ros::set_float rlFingerSpeedSrv;
   365   webots_ros::set_float rrFingerSpeedSrv;
   367   webots_ros::set_float llFingerSpeedSrv;
   369   webots_ros::set_float lrFingerSpeedSrv;
   371   webots_ros::set_float lShoulderRollSpeedSrv;
   373   webots_ros::set_float rShoulderRollSpeedSrv;
   386   webots_ros::sensor_set setSensorSrv;
   410   fllWheelAccelerationClient =
   412   flrWheelAccelerationClient =
   414   frlWheelAccelerationClient =
   416   frrWheelAccelerationClient =
   418   bllWheelAccelerationClient =
   420   blrWheelAccelerationClient =
   422   brlWheelAccelerationClient =
   424   brrWheelAccelerationClient =
   458   flRotationSetClient =
   477   fllWheelAccelerationClient.call(fllWheelAccelerationSrv);
   479   flrWheelAccelerationClient.call(flrWheelAccelerationSrv);
   481   frlWheelAccelerationClient.call(frlWheelAccelerationSrv);
   483   frrWheelAccelerationClient.call(frrWheelAccelerationSrv);
   485   bllWheelAccelerationClient.call(bllWheelAccelerationSrv);
   487   blrWheelAccelerationClient.call(blrWheelAccelerationSrv);
   489   brlWheelAccelerationClient.call(brlWheelAccelerationSrv);
   491   brrWheelAccelerationClient.call(brrWheelAccelerationSrv);
   493   fllWheelSetClient.call(setSensorSrv);
   494   flRotationSetClient.call(setSensorSrv);
   495   torsoSetClient.call(setSensorSrv);
   496   llFingerSetClient.call(setSensorSrv);
   497   rrFingerSetClient.call(setSensorSrv);
   498   lShoulderSetClient.call(setSensorSrv);
   499   rShoulderSetClient.call(setSensorSrv);
   500   lBumperSetClient.call(setSensorSrv);
   501   rBumperSetClient.call(setSensorSrv);
   502   imuSetClient.call(setSensorSrv);
   503   cameraSetClient.call(setSensorSrv);
   521   double finger_pos = 0;
   524   lShoulderLiftSrv.request.value = 1.35;
   525   lShoulderLiftClient.call(lShoulderLiftSrv);
   526   rShoulderLiftSrv.request.value = 1.35;
   527   rShoulderLiftClient.call(rShoulderLiftSrv);
   528   lElbowLiftSrv.request.value = -2.2;
   529   lElbowLiftClient.call(lElbowLiftSrv);
   530   rElbowLiftSrv.request.value = -2.2;
   531   rElbowLiftClient.call(rElbowLiftSrv);
   532   llFingerSrv.request.value = 0.4;
   533   llFingerClient.call(llFingerSrv);
   534   lrFingerSrv.request.value = 0.4;
   535   lrFingerClient.call(lrFingerSrv);
   536   rlFingerSrv.request.value = 0.05;
   537   rlFingerClient.call(rlFingerSrv);
   538   rrFingerSrv.request.value = 0.2;
   539   rrFingerClient.call(rrFingerSrv);
   540   torsoSrv.request.value = 0.33;
   541   torsoClient.call(torsoSrv);
   546       ROS_ERROR(
"Failed to call service time_step for next step.");
   560     else if (
imu_rpy[2] > -2.75 && sequence < 3) {
   562         ROS_INFO(
"PR2 rotates to face the fridge.");
   578         ROS_INFO(
"PR2 moves to the fridge.");
   588         ROS_INFO(
"PR2 places its right hand in front of the door's handle.");
   590         rShoulderRollSrv.request.value = 0.41;
   591         rShoulderRollClient.call(rShoulderRollSrv);
   592         rShoulderRollSpeedSrv.request.value = 0.21;
   593         rShoulderRollSpeedClient.call(rShoulderRollSpeedSrv);
   594         rShoulderLiftSrv.request.value = -0.3;
   595         rShoulderLiftClient.call(rShoulderLiftSrv);
   596         ruArmRollSrv.request.value = -3.14;
   597         ruArmRollClient.call(ruArmRollSrv);
   598         rElbowLiftSrv.request.value = -0.3;
   599         rElbowLiftClient.call(rElbowLiftSrv);
   600         rWristRollSrv.request.value = 1.57;
   601         rWristRollClient.call(rWristRollSrv);
   617     else if (!
rBumper && sequence < 8) {
   620         rlFingerSrv.request.value = 0;
   621         rlFingerClient.call(rlFingerSrv);
   622         rrFingerSrv.request.value = 0;
   623         rrFingerClient.call(rrFingerSrv);
   633         rlFingerSpeedSrv.request.value = 0;
   634         rlFingerSpeedClient.call(rlFingerSpeedSrv);
   635         rrFingerSpeedSrv.request.value = 0;
   636         rrFingerSpeedClient.call(rrFingerSpeedSrv);
   637         rShoulderRollSrv.request.value = -0.25;
   638         rShoulderRollClient.call(rShoulderRollSrv);
   647         rlFingerSrv.request.value = 0.4;
   648         rlFingerClient.call(rlFingerSrv);
   649         rrFingerSrv.request.value = 0.4;
   650         rrFingerClient.call(rrFingerSrv);
   651         rlFingerSpeedSrv.request.value = 0.2;
   652         rlFingerSpeedClient.call(rlFingerSpeedSrv);
   653         rrFingerSpeedSrv.request.value = 0.2;
   654         rrFingerSpeedClient.call(rrFingerSpeedSrv);
   655         rShoulderRollSrv.request.value = -0.5;
   656         rShoulderRollClient.call(rShoulderRollSrv);
   657         rShoulderRollSpeedSrv.request.value = 1;
   658         rShoulderRollSpeedClient.call(rShoulderRollSpeedSrv);
   667         lShoulderLiftSrv.request.value = 0;
   668         lShoulderLiftClient.call(lShoulderLiftSrv);
   669         rShoulderLiftSrv.request.value = 1.2;
   670         rShoulderLiftClient.call(rShoulderLiftSrv);
   671         ruArmRollSrv.request.value = 0;
   672         ruArmRollClient.call(ruArmRollSrv);
   673         lElbowLiftSrv.request.value = 0;
   674         lElbowLiftClient.call(lElbowLiftSrv);
   681       if (sequence == 10) {
   683         rElbowLiftSrv.request.value = -2.3;
   684         rElbowLiftClient.call(rElbowLiftSrv);
   685         lShoulderRollSrv.request.value = -0.57;
   686         lShoulderRollClient.call(lShoulderRollSrv);
   687         lShoulderRollSpeedSrv.request.value = 0.6;
   688         lShoulderRollSpeedClient.call(lShoulderRollSpeedSrv);
   691     } 
else if (step < 1260 && sequence < 13) {
   692       if (sequence == 11) {
   693         headTiltSrv.request.value = 0.4;
   694         headTiltClient.call(headTiltSrv);
   700       if (sequence == 12) {
   701         ROS_INFO(
"PR2 moves closer to the fridge.");
   703         rShoulderRollSrv.request.value = -0.1;
   704         rShoulderRollClient.call(rShoulderRollSrv);
   705         lShoulderLiftSrv.request.value = 0.65;
   706         lShoulderLiftClient.call(lShoulderLiftSrv);
   707         lElbowLiftSrv.request.value = -0.65;
   708         lElbowLiftClient.call(lElbowLiftSrv);
   709         lShoulderRollSrv.request.value = -0.48;
   710         lShoulderRollClient.call(lShoulderRollSrv);
   711         lShoulderRollSpeedSrv.request.value = 0.01;
   712         lShoulderRollSpeedClient.call(lShoulderRollSpeedSrv);
   718       if (sequence == 13) {
   719         ROS_INFO(
"PR2 moves its left-hand around the can.");
   721         lShoulderRollSrv.request.value = -0.235;
   722         lShoulderRollClient.call(lShoulderRollSrv);
   723         lShoulderRollSpeedSrv.request.value = 1;
   724         lShoulderRollSpeedClient.call(lShoulderRollSpeedSrv);
   730       if (sequence == 14) {
   741       if (sequence == 15) {
   744         llFingerSrv.request.value = 0;
   745         llFingerClient.call(llFingerSrv);
   746         lrFingerSrv.request.value = 0;
   747         lrFingerClient.call(lrFingerSrv);
   748         llFingerSpeedSrv.request.value = 0.015;
   749         llFingerSpeedClient.call(llFingerSpeedSrv);
   750         lrFingerSpeedSrv.request.value = 0.015;
   751         lrFingerSpeedClient.call(lrFingerSpeedSrv);
   752         llFingerTipSrv.request.value = 0.4;
   753         llFingerTipClient.call(llFingerTipSrv);
   754         lrFingerTipSrv.request.value = 0.4;
   755         lrFingerTipClient.call(lrFingerTipSrv);
   767       if (sequence == 16) {
   772         llFingerSpeedSrv.request.value = 0;
   773         llFingerSpeedClient.call(llFingerSpeedSrv);
   774         lrFingerSpeedSrv.request.value = 0;
   775         lrFingerSpeedClient.call(lrFingerSpeedSrv);
   781       if (sequence == 17) {
   783         rShoulderRollSrv.request.value = -0.6;
   784         rShoulderRollClient.call(rShoulderRollSrv);
   790       if (sequence == 18) {
   792         rShoulderLiftSrv.request.value = 0;
   793         rShoulderLiftClient.call(rShoulderLiftSrv);
   794         rElbowLiftSrv.request.value = 0;
   795         rElbowLiftClient.call(rElbowLiftSrv);
   801       if (sequence == 19) {
   804         rShoulderRollSrv.request.value = 0.5;
   805         rShoulderRollClient.call(rShoulderRollSrv);
   806         rShoulderRollSpeedSrv.request.value = 0.18;
   807         rShoulderRollSpeedClient.call(rShoulderRollSpeedSrv);
   808         lShoulderRollSrv.request.value = 0;
   809         lShoulderRollClient.call(lShoulderRollSrv);
   810         lShoulderLiftSrv.request.value = 1;
   811         lShoulderLiftClient.call(lShoulderLiftSrv);
   812         lElbowLiftSrv.request.value = -1;
   813         lElbowLiftClient.call(lElbowLiftSrv);
   814         flRotationSetClient.call(setSensorSrv);
   815         flRotationSubscriber =
   820       if (sequence == 20) {
   821         rShoulderRollSrv.request.value = 0.2;
   822         rShoulderRollClient.call(rShoulderRollSrv);
   829       if (sequence == 21) {
   831         imuSetClient.call(setSensorSrv);
   838     else if (
imu_rpy[2] < -0.35 && sequence < 24) {
   839       if (sequence == 22) {
   840         ROS_INFO(
"PR2 rotates back to go to the lounge.");
   842         rShoulderRollSrv.request.value = 0;
   843         rShoulderRollClient.call(rShoulderRollSrv);
   844         rShoulderLiftSrv.request.value = 1.35;
   845         rShoulderLiftClient.call(rShoulderLiftSrv);
   846         rElbowLiftSrv.request.value = -2.2;
   847         rElbowLiftClient.call(rElbowLiftSrv);
   848         rWristRollSrv.request.value = 0;
   849         rWristRollClient.call(rWristRollSrv);
   855       if (sequence == 23) {
   863       if (sequence == 24) {
   870       if (sequence == 25) {
   872         imuSetClient.call(setSensorSrv);
   878     else if (
imu_rpy[2] > -1.15 && sequence < 28) {
   879       if (sequence == 26) {
   881         torsoSetClient.call(setSensorSrv);
   889       if (sequence == 27) {
   890         ROS_INFO(
"PR2 slowly lay the can on the table.");
   892         torsoSrv.request.value = 0.165;
   893         torsoClient.call(torsoSrv);
   895         llFingerSetClient.call(setSensorSrv);
   902       if (sequence == 28) {
   903         ROS_INFO(
"PR2 release the can and go back to stand-by position.");
   904         llFingerSrv.request.value = 0.4;
   905         llFingerClient.call(llFingerSrv);
   906         lrFingerSrv.request.value = 0.4;
   907         lrFingerClient.call(lrFingerSrv);
   908         llFingerTipSrv.request.value = 0;
   909         llFingerTipClient.call(llFingerTipSrv);
   910         lrFingerTipSrv.request.value = 0;
   911         lrFingerTipClient.call(lrFingerTipSrv);
   912         llFingerSpeedSrv.request.value = 0.1;
   913         llFingerSpeedClient.call(llFingerSpeedSrv);
   914         lrFingerSpeedSrv.request.value = 0.1;
   915         lrFingerSpeedClient.call(lrFingerSpeedSrv);
   920     else if (sequence == 29) {
   921       lElbowLiftSrv.request.value = -2.2;
   922       lElbowLiftClient.call(lElbowLiftSrv);
   923       lShoulderLiftSrv.request.value = 1.35;
   924       lShoulderLiftClient.call(lShoulderLiftSrv);
   930   setSensorSrv.request.period = 0;
 ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void rrFingerCallback(const std_msgs::Float64::ConstPtr &value)
webots_ros::set_float frrWheelPositionSrv
int main(int argc, char **argv)
static std::vector< std::string > controllerList
static unsigned int lBumper
static std::string controllerName
ros::ServiceClient fllWheelPositionClient
webots_ros::set_float blRotationSrv
ros::ServiceClient bllWheelSpeedClient
webots_ros::set_float fllWheelSpeedSrv
ros::ServiceClient brRotationClient
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
webots_ros::set_float brlWheelPositionSrv
void rotate_wheels(double angle)
ros::ServiceClient blrWheelPositionClient
webots_ros::set_float flRotationSrv
webots_ros::set_float fllWheelPositionSrv
ros::ServiceClient brrWheelPositionClient
void imuCallback(const std_msgs::Float64MultiArray::ConstPtr &values)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::ServiceClient frrWheelSpeedClient
bool call(MReq &req, MRes &res)
static int controllerCount
void llFingerCallback(const std_msgs::Float64::ConstPtr &value)
ros::ServiceClient bllWheelPositionClient
void fllWheelCallback(const std_msgs::Float64::ConstPtr &value)
webots_ros::set_float brrWheelSpeedSrv
ros::ServiceClient timeStepClient
ros::ServiceClient frlWheelPositionClient
webots_ros::set_float bllWheelPositionSrv
static double rShoulderPosition
ros::ServiceClient blrWheelSpeedClient
static double llFingerPosition
void rBumperCallback(const std_msgs::Float64::ConstPtr &value)
webots_ros::set_float frRotationSrv
ros::ServiceClient brlWheelSpeedClient
webots_ros::set_int timeStepSrv
void flRotationCallback(const std_msgs::Float64::ConstPtr &value)
webots_ros::set_float frlWheelSpeedSrv
webots_ros::set_float brrWheelPositionSrv
webots_ros::set_float flrWheelSpeedSrv
static double wheelPosition
ros::ServiceClient frRotationClient
void torsoCallback(const std_msgs::Float64::ConstPtr &value)
uint32_t getNumPublishers() const 
void lBumperCallback(const std_msgs::Float64::ConstPtr &value)
webots_ros::set_float bllWheelSpeedSrv
ros::ServiceClient brlWheelPositionClient
void controllerNameCallback(const std_msgs::String::ConstPtr &name)
webots_ros::set_float brRotationSrv
ros::ServiceClient fllWheelSpeedClient
static double rrFingerPosition
static unsigned int rBumper
ros::ServiceClient blRotationClient
ros::ServiceClient brrWheelSpeedClient
void lShoulderCallback(const std_msgs::Float64::ConstPtr &value)
static double torsoPosition
webots_ros::set_float blrWheelPositionSrv
void rShoulderCallback(const std_msgs::Float64::ConstPtr &value)
ROSCPP_DECL void shutdown()
webots_ros::set_float brlWheelSpeedSrv
static double lShoulderPosition
ros::ServiceClient flRotationClient
webots_ros::set_float frlWheelPositionSrv
ros::ServiceClient frrWheelPositionClient
ros::ServiceClient frlWheelSpeedClient
static double rotationPosition
webots_ros::set_float frrWheelSpeedSrv
ROSCPP_DECL void spinOnce()
webots_ros::set_float flrWheelPositionSrv
void rotate(double speed)
ros::ServiceClient flrWheelSpeedClient
ros::ServiceClient flrWheelPositionClient
webots_ros::set_float blrWheelSpeedSrv