Skip to content

Commit

Permalink
Merge pull request #2217 from drcbot/mfallon-relabel-director
Browse files Browse the repository at this point in the history
relabel designer and ddapp to be called director

>> I think the .pmd files need ddConsoleApp --> director
... I just fixed this, merging.
  • Loading branch information
Maurice Fallon committed Nov 18, 2015
2 parents 51093b0 + 05880d0 commit d4e1f3a
Show file tree
Hide file tree
Showing 31 changed files with 71 additions and 71 deletions.
2 changes: 1 addition & 1 deletion .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
path = software/pronto
url = [email protected]:openhumanoids/pronto.git
[submodule "software/ddapp"]
path = software/ddapp
path = software/director
url = [email protected]:RobotLocomotion/director.git
[submodule "software/motion_estimate/signal-scope"]
path = software/motion_estimate/signal-scope
Expand Down
8 changes: 4 additions & 4 deletions catkin_ws/src/drc_translators/src/lcm2ros_ihmc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,10 +141,10 @@ LCM2ROS::LCM2ROS(boost::shared_ptr<lcm::LCM> &lcm_in, ros::NodeHandle &nh_in, st
10);

lcm_->subscribe("VAL_COMMAND_PAUSE", &LCM2ROS::pauseHandler, this);
lcm_->subscribe("STOP_WALKING", &LCM2ROS::stopHandler, this); // from drake-designer
lcm_->subscribe("STOP_WALKING", &LCM2ROS::stopHandler, this); // from Director
pause_pub_ = nh_.advertise<ihmc_msgs::PauseCommandMessage>("/ihmc_ros/" + robotName_ + "/control/pause_footstep_exec",
10);
lcm_->subscribe("COMMITTED_PLAN_PAUSE", &LCM2ROS::stopManipHandler, this); // from ddapp to stop manipulation plans
lcm_->subscribe("COMMITTED_PLAN_PAUSE", &LCM2ROS::stopManipHandler, this); // from Director to stop manipulation plans
stop_manip_pub_ = nh_.advertise<ihmc_msgs::StopMotionPacketMessage>(
"/ihmc_ros/" + robotName_ + "/control/stop_motion", 10);

Expand Down Expand Up @@ -342,7 +342,7 @@ void LCM2ROS::pauseHandler(const lcm::ReceiveBuffer* rbuf, const std::string &ch

void LCM2ROS::stopHandler(const lcm::ReceiveBuffer* rbuf, const std::string &channel, const drc::plan_control_t* msg)
{
ROS_ERROR("LCM2ROS got drake-designer - sending pause=true");
ROS_ERROR("LCM2ROS got STOP_WALKING - sending pause=true");
ihmc_msgs::PauseCommandMessage mout;
mout.pause = true;
pause_pub_.publish(mout);
Expand All @@ -351,7 +351,7 @@ void LCM2ROS::stopHandler(const lcm::ReceiveBuffer* rbuf, const std::string &cha
void LCM2ROS::stopManipHandler(const lcm::ReceiveBuffer* rbuf, const std::string &channel,
const drc::plan_control_t* msg)
{
ROS_ERROR("LCM2ROS got drake-designer - sending manipulate stop");
ROS_ERROR("LCM2ROS got COMMITTED_PLAN_PAUSE - sending manipulate stop");
ihmc_msgs::StopMotionPacketMessage mout;
mout.unique_id = msg->utime;
stop_manip_pub_.publish(mout);
Expand Down
4 changes: 2 additions & 2 deletions catkin_ws/src/drc_translators/src/ros2lcm_ihmc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,10 +304,10 @@ void App::behaviorCallback(const std_msgs::Int32ConstPtr& msg)
// IHMC publish: 3 when standing or manipulating, 4 when walking (as atlas_behavior_t)
// BDI publishs: 3 stand, 4 walk, 5 step, 6 manip (as atlas_behavior_t)
// MIT publish: 1 stand, 2 walk, 8 mani (as plan_status_t)
// We (i.e. ddapp) need either:
// We (i.e. the Direct) need either:
// - drc.atlas_behavior_t which comes from BDI typically) - and matches with IHMC output
// - drc.plan_status_t which comes from MIT controller typically) - typically atlas_behavior_t is 'user' than
// ddapp requires plan_status_t messages for autonomy. (pronto uses controller_status_t to contact ground points)
// Director requires plan_status_t messages for autonomy. (pronto uses controller_status_t to contact ground points)
bool behaviorMode = 0;

if (behaviorMode == 0)
Expand Down
4 changes: 2 additions & 2 deletions ipab-distro/bootstrap.sh
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ cd drc
git remote add sandbox [email protected]:drcbot/main-distro.git
git fetch sandbox

cd software/ddapp
cd software/director
git remote add sandbox [email protected]:openhumanoids/director.git
git fetch sandbox

Expand All @@ -20,4 +20,4 @@ echo "alias init_drc='source ~/ipab-distro/drc/software/config/drc_environment.s

mkdir -p ~/Documents/MATLAB
touch ~/Documents/MATLAB/startup.m
echo "run([getenv('DRC_BASE'), '/software/build/config/drc_control_setup.m'])" >> ~/Documents/MATLAB/startup.m # TODO check whether already there
echo "run([getenv('DRC_BASE'), '/software/build/config/drc_control_setup.m'])" >> ~/Documents/MATLAB/startup.m # TODO check whether already there
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,14 @@ group "4.exotica" {
}
}

cmd "drake-designer" {
exec = "drake-designer -lwr -exo -c $DRC_BASE/software/config/kuka_lwr.cfg --startup $DRC_BASE/../tests/systemtests/src/exoticaLWR/test.py";
cmd "director" {
exec = "director -lwr -exo -c $DRC_BASE/software/config/kuka_lwr.cfg --startup $DRC_BASE/../tests/systemtests/src/exoticaLWR/test.py";
host = "localhost";
}

script "start" {
start group "0.params_and_model_pub";
start cmd "exotica_json AICO" wait "running";
wait ms 1000;
start cmd "drake-designer" wait "stopped";
start cmd "director" wait "stopped";
}
2 changes: 1 addition & 1 deletion ipab-distro/tests/systemtests/src/exoticaLWR/test.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from ddapp import transformUtils
from director import transformUtils
import numpy

if ikPlanner.pushToMatlab==True:
Expand Down
8 changes: 4 additions & 4 deletions ipab-distro/tests/systemtests/src/generic_test.bash
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ sleep 1
$DRC_BASE/software/ipab/config/runscs.bash &
# Get the bash pid.
pidscs=$!
ddapp=0
director=0
sleep 1
pid="$(ps --ppid $pidscs | grep java | awk '{print $1;}')"

Expand All @@ -27,7 +27,7 @@ while [ $T -gt 0 ]; do
kill $pidcore > /dev/null 2>&1
exit 1
fi
if [[ $ddapp -eq 1 ]]; then
if [[ $director -eq 1 ]]; then
# When sheriff stops, check the status value
if ! kill -0 $pidsh > /dev/null 2>&1; then
if [[ "$(cat $SYSTEMTEST_RESULT_FILE)" -eq 0 ]]; then
Expand All @@ -47,12 +47,12 @@ while [ $T -gt 0 ]; do
else
if [ "$(rostopic info /ihmc_ros/valkyrie/api_command | grep Subscribers)" == "Subscribers: " ] ; then
# SCS is running now, send commands.
echo "SCS is ready, starting Drake Designer"
echo "SCS is ready, starting Director"
pid="$(ps --ppid $pidscs | grep java | awk '{print $1;}')"
bot-procman-sheriff -l -n $PROCMAN_SCRIPT start &
# Get the sheriff's pid.
pidsh=$!
ddapp=1
director=1
else
echo "Waiting for SCS to start ..."
fi
Expand Down
6 changes: 3 additions & 3 deletions ipab-distro/tests/systemtests/src/valWalk/v2.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,8 @@ group "4.maps" {
}
}

cmd "drake-designer" {
exec = "drake-designer -c $DRC_BASE/software/config/simul_robot_ihmc.cfg -val2 --startup $DRC_BASE/../tests/systemtests/src/valWalk/test.py";
cmd "director" {
exec = "director -c $DRC_BASE/software/config/simul_robot_ihmc.cfg -val2 --startup $DRC_BASE/../tests/systemtests/src/valWalk/test.py";
host = "localhost";
}

Expand All @@ -72,6 +72,6 @@ script "start" {
start group "2.state_without_pronto";
start group "3.plan_and_control";
start group "4.maps";
start cmd "drake-designer" wait "stopped";
start cmd "director" wait "stopped";
}

12 changes: 6 additions & 6 deletions software/config/atlas/robot.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -172,22 +172,22 @@ group "09.BDI_walking" {

group "10.Driving" {
cmd "Streaming Robot Side" {
exec = "DISPLAY=:0 ddConsoleApp $DRC_BASE/software/ddapp/src/python/tests/testAtlasCommand.py --robot";
exec = "DISPLAY=:0 directorPython $DRC_BASE/software/director/src/python/tests/testAtlasCommand.py --robot";
host = "atlas2";
}

cmd "Streaming Robot Side with Driving Gains" {
exec = "DISPLAY=:0 ddConsoleApp $DRC_BASE/software/ddapp/src/python/tests/testAtlasCommand.py --robotDrivingGains";
exec = "DISPLAY=:0 directorPython $DRC_BASE/software/director/src/python/tests/testAtlasCommand.py --robotDrivingGains";
host = "atlas2";
}

cmd "Streaming Base Side" {
exec = "ddConsoleApp $DRC_BASE/software/ddapp/src/python/tests/testAtlasCommand.py --base";
exec = "directorPython $DRC_BASE/software/director/src/python/tests/testAtlasCommand.py --base";
host = "base";
}

cmd "Throttle Driver" {
exec = "ddConsoleApp $DRC_BASE/software/ddapp/src/python/ddapp/triggerfinger.py THROTTLE_COMMAND ";
exec = "directorPython $DRC_BASE/software/director/src/python/director/triggerfinger.py THROTTLE_COMMAND ";
host = "base";
}

Expand All @@ -205,7 +205,7 @@ group "10.Driving" {

group "11.Video" {
cmd "Camera Viewer" {
exec = "ddConsoleApp $DRC_BASE/software/ddapp/src/python/scripts/cameraViewer.py";
exec = "directorPython $DRC_BASE/software/director/src/python/scripts/cameraViewer.py";
host = "base";
}

Expand Down Expand Up @@ -236,7 +236,7 @@ cmd "pose-util" {
}

cmd "atlas control panel" {
exec = "ddConsoleApp $DRC_BASE/software/ddapp/src/python/scripts/atlasControlPanel.py";
exec = "directorPython $DRC_BASE/software/director/src/python/scripts/atlasControlPanel.py";
host = "base";
}

Expand Down
2 changes: 1 addition & 1 deletion software/config/atlas_sim_mit/robot_v3.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ cmd "pose-util" {
}

cmd "director" {
exec = "drake-designer -c robot.cfg -v3";
exec = "director -c robot.cfg -v3";
host = "base";
}

Expand Down
2 changes: 1 addition & 1 deletion software/config/atlas_sim_mit/robot_v4.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ cmd "pose-util" {
}

cmd "director" {
exec = "drake-designer -c robot.cfg -v4";
exec = "director -c robot.cfg -v4";
host = "base";
}

Expand Down
4 changes: 2 additions & 2 deletions software/config/atlas_sim_mit/robot_v4_network_split.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -143,12 +143,12 @@ cmd "pose-util" {
}

cmd "director" {
exec = "drake-designer -c robot.cfg -v4";
exec = "director -c robot.cfg -v4";
host = "base";
}

cmd "robot-side-director" {
exec = "drake-designer -c robot.cfg -v4";
exec = "director -c robot.cfg -v4";
host = "atlas0";
}

Expand Down
2 changes: 1 addition & 1 deletion software/config/atlas_sim_mit/robot_v5.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ cmd "pose-util" {
}

cmd "director" {
exec = "drake-designer -c robot.cfg -v5";
exec = "director -c robot.cfg -v5";
host = "base";
}

Expand Down
8 changes: 4 additions & 4 deletions software/config/atlas_sim_scs/robot.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,8 @@ group "4.maps" {
}


cmd "drake-designer" {
exec = "drake-designer -c $DRC_BASE/software/config/atlas_sim_scs/robot.cfg -v5";
cmd "director" {
exec = "director -c $DRC_BASE/software/config/atlas_sim_scs/robot.cfg -v5";
host = "localhost";
}

Expand All @@ -108,7 +108,7 @@ script "start_ui" {
start group "2.state_without_pronto";
start group "3.plan_and_control";
start group "4.maps";
start cmd "drake-designer";
start cmd "director";
}

script "start_ui_with_pronto" {
Expand All @@ -118,6 +118,6 @@ script "start_ui_with_pronto" {
start group "2.state_with_pronto";
start group "3.plan_and_control";
start group "4.maps";
start cmd "drake-designer";
start cmd "director";
}

4 changes: 2 additions & 2 deletions software/config/husky/robot.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ group "2.vis" {
}


cmd "designer" {
exec = "drake-designer -c $DRC_BASE/software/config/husky/robot.cfg";
cmd "director" {
exec = "director -c $DRC_BASE/software/config/husky/robot.cfg";
host = "localhost";
}
}
Expand Down
4 changes: 2 additions & 2 deletions software/config/husky/standalone_multisense.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ group "2.vis" {
}


cmd "designer" {
exec = "drake-designer -c $DRC_BASE/software/config/husky/robot.cfg";
cmd "director" {
exec = "director -c $DRC_BASE/software/config/husky/robot.cfg";
host = "localhost";
}
}
Expand Down
2 changes: 1 addition & 1 deletion software/config/irb140/simul_irb140.pmd
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmd "director" {
exec = "drake-designer --director_config $DRC_BASE/software/models/IRB140/director_config.json";
exec = "director --director_config $DRC_BASE/software/models/IRB140/director_config.json";
host = "base";
}

Expand Down
6 changes: 3 additions & 3 deletions software/config/kuka_lwr/robot.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,8 @@ group "4.mapping" {
}
}

cmd "drake-designer" {
exec = "drake-designer -lwr -c $DRC_BASE/software/config/kuka_lwr.cfg";
cmd "director" {
exec = "director -lwr -c $DRC_BASE/software/config/kuka_lwr.cfg";
host = "localhost";
}

Expand All @@ -77,5 +77,5 @@ script "start" {
wait ms 1000;
start group "1.state";
start group "2.sensors";
start cmd "drake-designer";
start cmd "director";
}
6 changes: 3 additions & 3 deletions software/config/kuka_lwr/robot_exotica.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ group "4.exotica" {
}
}

cmd "drake-designer" {
exec = "drake-designer -lwr -exo -c $DRC_BASE/software/config/kuka_lwr.cfg";
cmd "director" {
exec = "director -lwr -exo -c $DRC_BASE/software/config/kuka_lwr.cfg";
host = "localhost";
}

Expand All @@ -89,5 +89,5 @@ script "start" {
start group "0.params_and_model_pub";
start cmd "exotica_json AICO";
wait ms 1000;
start cmd "drake-designer";
start cmd "director";
}
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ cmd "microstrain_from_sudo" {
host = "localhost";
}

cmd "drake-designer" {
exec = "drake-designer";
cmd "director" {
exec = "director";
host = "localhost";
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ cmd "viewer" {
}


cmd "designer" {
exec = "drake-designer -v4 -c $DRC_BASE/software/config/drc_robot.cfg";
cmd "director" {
exec = "director -v4 -c $DRC_BASE/software/config/drc_robot.cfg";
host = "localhost";
}
8 changes: 4 additions & 4 deletions software/config/val_sim_scs/robot.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,8 @@ group "4.maps" {
}


cmd "drake-designer" {
exec = "drake-designer -c $DRC_BASE/software/config/val_sim_scs/robot.cfg -val2";
cmd "director" {
exec = "director -c $DRC_BASE/software/config/val_sim_scs/robot.cfg -val2";
host = "localhost";
}

Expand All @@ -114,7 +114,7 @@ script "start_ui" {
start group "2.state_without_pronto";
start group "3.plan_and_control";
start group "4.maps";
start cmd "drake-designer";
start cmd "director";
}

script "start_ui_with_pronto" {
Expand All @@ -124,7 +124,7 @@ script "start_ui_with_pronto" {
start group "2.state_with_pronto";
start group "3.plan_and_control";
start group "4.maps";
start cmd "drake-designer";
start cmd "director";
}

script "start_ui_with_scs" {
Expand Down
2 changes: 1 addition & 1 deletion software/config/video_capture.pmd
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ group "start" {
}

cmd "server" {
exec = "bash -c 'LCM_DEFAULT_URL=udpm://239.255.76.50:7650?ttl=0 python $HOME/drc/software/ddapp/src/python/scripts/videoLogServer.py $HOME/logs/video-logs'";
exec = "bash -c 'LCM_DEFAULT_URL=udpm://239.255.76.50:7650?ttl=0 python $HOME/drc/software/director/src/python/scripts/videoLogServer.py $HOME/logs/video-logs'";
host = "localhost";
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
r = options.robot;
end

addpath(fullfile(getDrakePath(), '../../', 'ddapp/src/matlab') )
addpath(fullfile(getDrakePath(), '../../', 'director/src/matlab') )
fixed_point_file = [getDrakePath(), '/../../control/matlab/data/val_description/valkyrie_fp_june2015.mat'];
left_foot_link = 'LeftFoot';
right_foot_link = 'RightFoot';
Expand Down
1 change: 0 additions & 1 deletion software/ddapp
Submodule ddapp deleted from fac3f0
1 change: 1 addition & 0 deletions software/director
Submodule director added at def94a
Loading

0 comments on commit d4e1f3a

Please sign in to comment.