@@ -34,6 +34,7 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
3434 // feedingDemo->getCollisionConstraintWithWallFurtherBack();
3535 const Eigen::Isometry3d &personPose = workspace->getPersonPose ();
3636 std::chrono::milliseconds waitAtPerson = feedingDemo->mWaitTimeForPerson ;
37+ bool useSound = feedingDemo->mUseSound ;
3738 double distanceToPerson = feedingDemo->mPersonTSRParameters .at (" distance" );
3839 double horizontalToleranceForPerson =
3940 feedingDemo->mPersonTSRParameters .at (" horizontalTolerance" );
@@ -60,7 +61,8 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
6061 moveIFOSuccess = moveIFOPerson ();
6162 if (!moveIFOSuccess) {
6263 ROS_WARN_STREAM (" Failed to move in front of person, retry" );
63- talk (" Sorry, I'm having a little trouble moving. Let me try again." );
64+ if (useSound)
65+ talk (" Sorry, I'm having a little trouble moving. Let me try again." );
6466 continue ;
6567 } else
6668 break ;
@@ -73,7 +75,8 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
7375 auto overrideTiltOffset = tiltOffset;
7476
7577 if (!getRosParam<bool >(" /humanStudy/autoTransfer" , *nodeHandle)) {
76- talk (" Should I tilt the food item?" , false );
78+ if (useSound)
79+ talk (" Should I tilt the food item?" , false );
7780 std::string done = " " ;
7881 std::string actionTopic;
7982 nodeHandle->param <std::string>(" /humanStudy/actionTopic" , actionTopic,
@@ -106,7 +109,8 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
106109
107110 // Check autoTiming, and if false, wait for topic
108111 if (!getRosParam<bool >(" /humanStudy/autoTiming" , *nodeHandle)) {
109- talk (" Let me know when you are ready." , false );
112+ if (useSound)
113+ talk (" Let me know when you are ready." , false );
110114 std::string done = " " ;
111115 while (done != " continue" ) {
112116 std::string actionTopic;
@@ -116,7 +120,8 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
116120 }
117121 } else {
118122 nodeHandle->setParam (" /feeding/facePerceptionOn" , true );
119- talk (" Open your mouth when ready." , false );
123+ if (useSound)
124+ talk (" Open your mouth when ready." , false );
120125 // TODO: Add mouth-open detection.
121126 while (true ) {
122127 std::this_thread::sleep_for (std::chrono::milliseconds (100 ));
@@ -132,7 +137,8 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
132137 if (getRosParam<bool >(" /humanStudy/createError" , *nodeHandle)) {
133138 // Wait an extra 5 seconds
134139 ROS_WARN_STREAM (" Error Requested for Timing!" );
135- talk (" Calculating..." );
140+ if (useSound)
141+ talk (" Calculating..." );
136142 std::this_thread::sleep_for (std::chrono::milliseconds (5000 ));
137143 }
138144 }
@@ -163,7 +169,8 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
163169 success = false ;
164170 }
165171 std::this_thread::sleep_for (std::chrono::milliseconds (3000 ));
166- talk (" Oops, let me try that again." , true );
172+ if (useSound)
173+ talk (" Oops, let me try that again." , true );
167174 moveIFOSuccess = moveInFrontOfPerson (
168175 ada->getArm ()->getSelfCollisionConstraint (), personPose,
169176 distanceToPerson, horizontalToleranceForPerson,
@@ -215,7 +222,8 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
215222 double slowFactor = (velocityLimits[0 ] > 0.5 ) ? 2.0 : 1.0 ;
216223 slowerVelocity /= slowFactor;
217224
218- talk (" Tilting, hold tight." , true );
225+ if (useSound)
226+ talk (" Tilting, hold tight." , true );
219227
220228 auto trajectory = ada->getArm ()->planToConfiguration (
221229 ada->getArm ()->getNamedConfiguration (" home_config" ),
@@ -261,12 +269,14 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
261269 if (moveIFOSuccess) {
262270 // ===== EATING =====
263271 ROS_WARN (" Human is eating" );
264- talk (" Ready to eat!" );
272+ if (useSound)
273+ talk (" Ready to eat!" );
265274 std::this_thread::sleep_for (waitAtPerson);
266275
267276 // Backward
268277 ada::util::waitForUser (" Move backward" , ada);
269- talk (" Let me get out of your way." , true );
278+ if (useSound)
279+ talk (" Let me get out of your way." , true );
270280 Eigen::Vector3d goalDirection (0 , -1 , 0 );
271281 bool success = moveInFrontOfPerson (
272282 ada->getArm ()->getWorldCollisionConstraint (
@@ -281,7 +291,8 @@ void feedFoodToPerson(const std::shared_ptr<Perception> &perception,
281291
282292 // TODO: add a back-out motion and then do move above plate with
283293 // collisionFree.
284- talk (" And now back to the plate." , true );
294+ // if (useSound)
295+ // talk("And now back to the plate.", true);
285296 moveAbovePlate (plate, plateEndEffectorTransform, feedingDemo);
286297
287298 publishTimingDoneToWeb ((ros::NodeHandle *)nodeHandle);
0 commit comments