Skip to content

Commit

Permalink
set default corbaport to 5005, Fixes Issue 141
Browse files Browse the repository at this point in the history
  • Loading branch information
kei.okada committed Aug 20, 2013
1 parent fb4d314 commit 2afa2cf
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 9 deletions.
10 changes: 6 additions & 4 deletions hrpsys_ros_bridge/launch/hrpsys_ros_bridge.launch
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,10 @@
-->
<!-- BEGIN:openrtm setting -->
<arg name="nameserver" default="localhost" />
<env name="RTCTREE_NAMESERVERS" value="$(arg nameserver)" />
<arg name="openrtm_args" default='-o "corba.nameservers:$(arg nameserver):2809" -o "naming.formats:%n.rtc" -o "exec_cxt.periodic.type:PeriodicExecutionContext" -o "exec_cxt.periodic.rate:2000" -o "logger.file_name:/tmp/rtc%p.log"' />
<arg name="corbaport" default="5005" />
<env name="RTCTREE_NAMESERVERS" value="$(arg nameserver):$(arg corbaport)" />
<arg name="omniorb_args" default="-ORBInitRef NameService=corbaloc:iiop:$(arg nameserver):$(arg corbaport)/NameService" />
<arg name="openrtm_args" default='-o "corba.nameservers:$(arg nameserver):$(arg corbaport)" -o "naming.formats:%n.rtc" -o "exec_cxt.periodic.type:PeriodicExecutionContext" -o "exec_cxt.periodic.rate:2000" -o "logger.file_name:/tmp/rtc%p.log"' />
<!-- END:openrtm setting -->
<arg name="OUTPUT" default="screen"/>
<env name="LANG" value="C" />
Expand All @@ -43,13 +45,13 @@

<!-- diagnostics -->
<node pkg="hrpsys_ros_bridge" name="hrpsys_ros_diagnostics" type="diagnostics.py" />
<node pkg="hrpsys_ros_bridge" name="hrpsys_profile" type="hrpsys_profile.py" />
<node pkg="hrpsys_ros_bridge" name="hrpsys_profile" type="hrpsys_profile.py" args="$(arg omniorb_args)"/>
<node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" >
<rosparam command="load" file="$(find hrpsys_ros_bridge)/scripts/diagnostics.yaml" />
</node>

<node pkg="hrpsys_ros_bridge" name="sensor_ros_bridge_connect" type="sensor_ros_bridge_connect.py"
args="$(arg MODEL_FILE) $(arg SIMULATOR_NAME) HrpsysSeqStateROSBridge0 $(arg nameserver) -ORBInitRef NameService=corbaloc:iiop:$(arg nameserver):2809/NameService" output="$(arg OUTPUT)"/>
args="$(arg MODEL_FILE) $(arg SIMULATOR_NAME) HrpsysSeqStateROSBridge0 $(arg nameserver) $(arg omniorb_args)" output="$(arg OUTPUT)"/>
<!-- BEGIN:openrtm connection -->
<env name="SIMULATOR_NAME" value="$(arg SIMULATOR_NAME)" />
<node name="rtmlaunch_hrpsys_ros_bridge" pkg="openrtm_tools" type="rtmlaunch.py" args="$(find hrpsys_ros_bridge)/launch/hrpsys_ros_bridge.launch USE_COMMON=$(arg USE_COMMON) USE_WALKING=$(arg USE_WALKING) USE_COLLISIONCHECK=$(arg USE_COLLISIONCHECK) USE_IMPEDANCECONTROLLER=$(arg USE_IMPEDANCECONTROLLER) USE_SOFTERRORLIMIT=$(arg USE_SOFTERRORLIMIT) USE_IMAGESENSOR=$(arg USE_IMAGESENSOR) USE_ROBOTHARDWARE=$(arg USE_ROBOTHARDWARE)"/>
Expand Down
2 changes: 1 addition & 1 deletion hrpsys_ros_bridge/scripts/rtmlaunch
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ if start_naming :
except:
pass

p = subprocess.Popen([cosnames,"-start", "-logdir", logdir])
p = subprocess.Popen([cosnames,"-start", "5005", "-always", "-logdir", logdir])


import roslaunch
Expand Down
9 changes: 6 additions & 3 deletions hrpsys_tools/launch/hrpsys.launch
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,11 @@

<!-- BEGIN:openrtm setting -->
<arg name="nameserver" default="localhost" />
<arg name="corbaport" default="5005" />
<arg name="KILL_SERVERS" default="false" />
<env name="RTCTREE_NAMESERVERS" value="$(arg nameserver)" />
<arg name="openrtm_args" default='-o "corba.nameservers:$(arg nameserver):2809" -o "naming.formats:%n.rtc" -o "logger.file_name:/tmp/rtc%p.log" ' />
<env name="RTCTREE_NAMESERVERS" value="$(arg nameserver):$(arg corbaport)" />
<arg name="omniorb_args" default="-ORBInitRef NameService=corbaloc:iiop:$(arg nameserver):$(arg corbaport)/NameService" />
<arg name="openrtm_args" default='-o "corba.nameservers:$(arg nameserver):$(arg corbaport)" -o "naming.formats:%n.rtc" -o "logger.file_name:/tmp/rtc%p.log" ' />
<!-- END:openrtm setting -->

<!-- BEGIN:setting for hrpsys-simulator or rtcd -->
Expand Down Expand Up @@ -83,6 +85,7 @@
</group>

<node name="modelloader" pkg="openhrp3" type="openhrp-model-loader"
args="$(arg omniorb_args)"
respawn="$(arg RESPAWN)" output="screen"
if="$(arg openrtm_openhrp_server_start)"/> <!-- loading dae files crushes model loader -->

Expand All @@ -99,7 +102,7 @@

<group if="$(arg LAUNCH_HRPSYSPY)">
<node name="hrpsys_py" pkg="$(arg HRPSYS_PY_PKG)" type="$(arg HRPSYS_PY_NAME)" output="screen"
args='$(arg SIMULATOR_NAME) $(arg MODEL_FILE)' />
args='$(arg SIMULATOR_NAME) $(arg MODEL_FILE) $(arg omniorb_args)' />
</group>

<!-- <node name="abstransform2posrpy" pkg="hrpsys" type="AbsTransformToPosRpy" output="$(arg OUTPUT)" -->
Expand Down
3 changes: 2 additions & 1 deletion openrtm_tools/scripts/rtshell-setup.sh
Original file line number Diff line number Diff line change
Expand Up @@ -10,5 +10,6 @@ else
echo -e "Warning : Failed to load shell_support, try rosmake openrtm"
fi

export RTCTREE_NAMESERVERS=localhost
export RTCTREE_NAMESERVERS=localhost:5005
complete -F "_roscomplete_launch" -o filenames "rtmlaunch"
#echo ";; set RTCTREE_NAMESERVERS=$RTCTREE_NAMESERVERS"

0 comments on commit 2afa2cf

Please sign in to comment.