Skip to content

Commit 2650ea7

Browse files
authored
Improved the Audio Interaction for the Demo (#9)
* Updated the Audio Pipeline for the Demo - Added a useSound command line flag that controls whether to output sound - Changed most talk(…) invocations to run in the background - Added a useAlexa parameter that dictates whether to wait to receive a food name from Alexa - Slightly changed the speech outputs over the course of the demo * Removed second DetectAndMoveAboveFood, changed grape's tiltStyle * Added useAlexa to gen3 config
1 parent b0b0575 commit 2650ea7

File tree

12 files changed

+122
-68
lines changed

12 files changed

+122
-68
lines changed

config/gen2_feeding_demo.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -121,14 +121,14 @@ foodItems:
121121
#pickUpAngleModes: [0, 2, 2, 0, 0, 0, 0]
122122
names: ["apple", "banana", "bell_pepper", "broccoli", "cantaloupe", "carrot", "cauliflower", "celery", "cherry_tomato", "grape", "honeydew", "kiwi", "strawberry", "lettuce", "spinach", "kale"]
123123
forces: [10, 10, 10, 10, 15, 22, 7, 22, 7, 10, 7, 7, 15, 7, 7, 7]
124-
pickUpAngleModes: [1, 5, 1, 2, 1, 1, 0, 1, 1, 3, 3, 3, 0, 1, 2, 0]
124+
pickUpAngleModes: [1, 5, 1, 2, 1, 1, 0, 1, 1, 1, 3, 3, 0, 1, 2, 0]
125125

126126
humanStudy:
127127
autoAcquisition: true
128128
autoTiming: true
129129
autoTransfer: true
130130
createError: false
131-
useAlexa: true
131+
useAlexa: false
132132
foodTopic: /alexa_msgs
133133
actionTopic: /alexa_msgs
134134

config/gen3_feeding_demo.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,7 @@ humanStudy:
130130
autoTiming: true
131131
autoTransfer: true
132132
createError: false
133+
useAlexa: false
133134
foodTopic: /study_food_msgs
134135
actionTopic: /study_action_msgs
135136

include/feeding/FeedingDemo.hpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,14 @@ class FeedingDemo {
3636
/// simulation.
3737
/// \param[in] useFTSensing turns the FTSensor and the
3838
/// MoveUntilTouchController on and off
39-
/// \param[in] useVisualServo If true, perception servo is used.
39+
/// \param[in] useVisualServo If true, perception servo is used.\
40+
/// \param[in] useSound If true, use audio to explain each step of the process.
4041
/// \param[in] allowFreeRotation, If true, items specified as rotationFree
4142
/// get rotational freedom.
4243
/// \param[in] nodeHandle Handle of the ros node.
4344
FeedingDemo(bool adaReal, std::shared_ptr<ros::NodeHandle> nodeHandle,
4445
bool useFTSensingToStopTrajectories, bool useVisualServo,
45-
bool allowFreeRotation,
46+
bool allowFreeRotation, bool useSound,
4647
std::shared_ptr<FTThresholdHelper> ftThresholdHelper = nullptr,
4748
bool autoContinueDemo = false);
4849

@@ -104,6 +105,9 @@ class FeedingDemo {
104105
std::unordered_map<std::string, double> mPersonTSRParameters;
105106
double mMoveOufOfFoodLength;
106107

108+
bool mUseSound;
109+
bool mUseAlexa;
110+
107111
double mPlanningTimeout;
108112
int mMaxNumTrials;
109113
int mBatchSize;

include/feeding/util.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ static aikido::rviz::InteractiveMarkerViewerPtr VIEWER;
4444
/// \param[out] dataCollectorPath Directory to store data collection
4545
/// on and off
4646
void handleArguments(int argc, char **argv, bool &adaReal,
47-
bool &autoContinueDemo, bool &useFTSensing,
47+
bool &autoContinueDemo, bool &useFTSensing, bool& useSound,
4848
std::string &demoType, std::string &foodName,
4949
std::size_t &directionIndex, std::size_t &trialIndex,
5050
std::string &dataCollectorPath,
@@ -61,7 +61,7 @@ void dumpSplinePhasePlot(const aikido::trajectory::Spline &spline,
6161
/// param[in] food_only If true, only food choices are valid
6262
/// param[in]] nodeHandle Ros Node to set food name for detection.
6363
std::string getUserFoodInput(bool food_only, ros::NodeHandle &nodeHandle,
64-
bool useAlexa = true, double timeout = 5);
64+
bool useAlexa = true, double timeout = 10);
6565

6666
int getUserInputWithOptions(const std::vector<std::string> &optionPrompts,
6767
const std::string &prompt);
@@ -101,7 +101,7 @@ std::string getInputFromTopic(std::string topic,
101101
const ros::NodeHandle &nodeHandle,
102102
bool validateAsFood, double timeout = 20);
103103

104-
void talk(const std::string &, bool background = false);
104+
void talk(const std::string&, bool background = true);
105105

106106
void initTopics(ros::NodeHandle *nodeHandle);
107107

scripts/demo.cpp

Lines changed: 37 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,10 @@ void demo(
3131
auto workspace = feedingDemo.getWorkspace();
3232
auto plate = workspace->getPlate()->getRootBodyNode()->getWorldTransform();
3333

34-
talk("Hello, my name is aid uh. It's my pleasure to serve you today!");
34+
bool useSound = feedingDemo.mUseSound;
35+
36+
if (useSound)
37+
talk("Hello, my name is aid uh. I'm your feeding companion!");
3538

3639
srand(time(NULL));
3740

@@ -40,9 +43,10 @@ void demo(
4043
if (feedingDemo.getFTThresholdHelper())
4144
feedingDemo.getFTThresholdHelper()->setThresholds(STANDARD_FT_THRESHOLD);
4245

43-
talk("What food would you like?");
46+
if (useSound)
47+
talk("What food would you like?", false);
4448

45-
auto foodName = getUserFoodInput(false, nodeHandle);// "cantaloupe";//
49+
auto foodName = getUserFoodInput(false, nodeHandle, feedingDemo.mUseAlexa);// "cantaloupe";//
4650
if (foodName == std::string("quit")) {
4751
break;
4852
}
@@ -55,34 +59,37 @@ void demo(
5559
ROS_INFO_STREAM("Running bite transfer study for " << foodName);
5660

5761
/*
58-
switch((rand() % 10)) {
59-
case 0:
60-
talk("Good choice!");
61-
break;
62-
case 1:
63-
talk(std::string("Great! I love ") + foodName + std::string("'s!"));
64-
break;
65-
case 2:
66-
talk("Sounds delicious. I wish I had taste buds.");
67-
break;
68-
case 4:
69-
talk("Roger Roger.");
70-
break;
71-
case 5:
72-
talk("Nothing beats fresh fruit.");
73-
break;
74-
case 6:
75-
talk("Nothing escapes my fork!");
76-
break;
77-
case 7:
78-
talk("Thanks Alexa!");
79-
break;
80-
default:
81-
talk("Alright.");
62+
if (useSound) {
63+
switch((rand() % 10)) {
64+
case 0:
65+
talk("Good choice!");
66+
break;
67+
case 1:
68+
talk(std::string("Great! I love ") + foodName + std::string("'s!"));
69+
break;
70+
case 2:
71+
talk("Sounds delicious. I wish I had taste buds.");
72+
break;
73+
case 4:
74+
talk("Roger Roger.");
75+
break;
76+
case 5:
77+
talk("Nothing beats fresh fruit.");
78+
break;
79+
case 6:
80+
talk("Nothing escapes my fork!");
81+
break;
82+
case 7:
83+
talk("Thanks Alexa!");
84+
break;
85+
default:
86+
talk("Alright.");
87+
}
8288
}
8389
*/
8490

85-
talk(std::string("One ") + foodName + std::string(" coming right up!"), true);
91+
if (useSound)
92+
talk(std::string("One ") + foodName + std::string(" coming right up!"), true);
8693

8794
// ===== FORQUE PICKUP =====
8895
if (foodName == "pickupfork")
@@ -135,6 +142,7 @@ void demo(
135142

136143
// ===== DONE =====
137144
ROS_INFO("Demo finished.");
138-
talk("Thank you, I hope I was helpful!");
145+
if (useSound)
146+
talk("Thank you, I look forward to feeding you again!");
139147
}
140148
};

scripts/main.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,9 @@ int main(int argc, char** argv)
4545
// the FT sensing can stop trajectories if the forces are too big
4646
bool useFTSensingToStopTrajectories = false;
4747

48+
// should the ADA speak between steps?
49+
bool useSound = false;
50+
4851
bool TERMINATE_AT_USER_PROMPT = true;
4952

5053
std::string demoType{"default"};
@@ -56,7 +59,7 @@ int main(int argc, char** argv)
5659
std::size_t trialIndex{0};
5760

5861
handleArguments(argc, argv,
59-
adaReal, autoContinueDemo, useFTSensingToStopTrajectories,
62+
adaReal, autoContinueDemo, useFTSensingToStopTrajectories, useSound,
6063
demoType, foodName, directionIndex, trialIndex, dataCollectorPath);
6164

6265
bool useVisualServo = true;
@@ -113,6 +116,7 @@ int main(int argc, char** argv)
113116
useFTSensingToStopTrajectories,
114117
useVisualServo,
115118
allowRotationFree,
119+
useSound,
116120
ftThresholdHelper,
117121
autoContinueDemo);
118122

src/FeedingDemo.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,12 +29,12 @@ namespace feeding {
2929
FeedingDemo::FeedingDemo(bool adaReal,
3030
std::shared_ptr<ros::NodeHandle> nodeHandle,
3131
bool useFTSensingToStopTrajectories,
32-
bool useVisualServo, bool allowFreeRotation,
32+
bool useVisualServo, bool allowFreeRotation, bool useSound,
3333
std::shared_ptr<FTThresholdHelper> ftThresholdHelper,
3434
bool autoContinueDemo)
3535
: mAdaReal(adaReal), mNodeHandle(nodeHandle),
3636
mFTThresholdHelper(ftThresholdHelper), mVisualServo(useVisualServo),
37-
mAllowRotationFree(allowFreeRotation),
37+
mAllowRotationFree(allowFreeRotation), mUseSound(useSound),
3838
mAutoContinueDemo(autoContinueDemo),
3939
mIsFTSensingEnabled(useFTSensingToStopTrajectories) {
4040
mWorld = std::make_shared<aikido::planner::World>("feeding");
@@ -167,6 +167,8 @@ FeedingDemo::FeedingDemo(bool adaReal,
167167
}
168168

169169
mTableHeight = getRosParam<double>("/study/tableHeight", *mNodeHandle);
170+
171+
mUseAlexa = getRosParam<bool>("/humanStudy/useAlexa", *mNodeHandle);
170172
}
171173

172174
//==============================================================================

src/action/DetectAndMoveAboveFood.cpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -20,14 +20,17 @@ detectAndMoveAboveFood(const std::shared_ptr<Perception> &perception,
2020
const std::string &foodName, double rotationTolerance,
2121
FeedingDemo *feedingDemo, double *angleGuess,
2222
int actionOverride) {
23+
bool useSound = feedingDemo->mUseSound;
24+
2325
std::vector<std::unique_ptr<FoodItem>> candidateItems;
2426
while (true) {
2527
// Perception returns the list of good candidates, any one of them is good.
2628
// Multiple candidates are preferrable since planning may fail.
2729
candidateItems = perception->perceiveFood(foodName);
2830

2931
if (candidateItems.size() == 0) {
30-
// talk("I can't find that food. Try putting it on the plate.");
32+
// if (useSound)
33+
// talk("I can't find that food. Try putting it on the plate.");
3134
ROS_WARN_STREAM(
3235
"Failed to detect any food. Please place food on the plate.");
3336
} else
@@ -58,7 +61,8 @@ detectAndMoveAboveFood(const std::shared_ptr<Perception> &perception,
5861
action->getTiltStyle(), rotationTolerance, feedingDemo, angleGuess);
5962
if (!moveAboveSuccessful) {
6063
ROS_INFO_STREAM("Failed to move above " << item->getName());
61-
talk("Sorry, I'm having a little trouble moving. Let's try again.");
64+
if (useSound)
65+
talk("Sorry, I'm having a little trouble moving. Let's try again.");
6266
return nullptr;
6367
}
6468

@@ -69,8 +73,10 @@ detectAndMoveAboveFood(const std::shared_ptr<Perception> &perception,
6973

7074
if (!moveAboveSuccessful) {
7175
ROS_ERROR("Failed to move above any food.");
72-
talk("Sorry, I'm having a little trouble moving. Mind if I get a little "
73-
"help?");
76+
if (useSound)
77+
talk(
78+
"Sorry, I'm having a little trouble moving. Mind if I get a little "
79+
"help?");
7480
return nullptr;
7581
}
7682

src/action/FeedFoodToPerson.cpp

Lines changed: 21 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -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);

src/action/MoveAbove.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ bool moveAbove(const Eigen::Isometry3d &targetTransform,
2020
// Load necessary parameters from feedingDemo
2121
const std::shared_ptr<::ada::Ada> &ada = feedingDemo->getAda();
2222
const CollisionFreePtr &collisionFree = feedingDemo->getCollisionConstraint();
23+
bool useSound = feedingDemo->mUseSound;
2324
double planningTimeout = feedingDemo->mPlanningTimeout;
2425
int maxNumTrials = feedingDemo->mMaxNumTrials;
2526
int batchSize = feedingDemo->mBatchSize;
@@ -83,7 +84,8 @@ bool moveAbove(const Eigen::Isometry3d &targetTransform,
8384

8485
} while (rotationTolerance <= 2.0);
8586
if (!trajectoryCompleted) {
86-
// talk("No trajectory, check T.S.R.", true);
87+
// if (useSound)
88+
// talk("No trajectory, check T.S.R.", true);
8789
if (feedingDemo && feedingDemo->getViewer()) {
8890
feedingDemo->getViewer()->addTSRMarker(target);
8991
std::cout << "Check TSR" << std::endl;

0 commit comments

Comments
 (0)