Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Merge after #1720] [jsk_robot_startup] Support manual setting of the name of database and collection #1801

Open
wants to merge 14 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
40 changes: 37 additions & 3 deletions jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,8 @@
<launch>
<!-- mongo setting -->
<arg name="database" default="jsk_robot_lifelog" />
<arg name="collection" default="USE_DEFAULT_VALUE" />

<!-- options -->
<arg name="save_rgb" default="true" />
<arg name="save_depth" default="true" />
Expand Down Expand Up @@ -36,8 +40,9 @@
<machine if="$(arg localhost)" name="localhost" address="localhost" />

<!-- nodelet -->
<arg name="ns" default="lifelog" />
<arg name="launch_manager" default="true" />
<arg if="$(arg launch_manager)" name="manager" default="mongodb_record_nodelet_manager" />
<arg if="$(arg launch_manager)" name="manager" default="mongodb_$(arg ns)_nodelet_manager" />
<arg unless="$(arg launch_manager)" name="manager" />

<!-- others -->
Expand All @@ -56,7 +61,7 @@
pkg="nodelet" type="nodelet" args="manager" machine="$(arg machine)"
output="screen" respawn="$(arg respawn)" launch-prefix="$(arg launch-prefix)"/>

<group ns="lifelog">
<group ns="$(arg ns)">
<!-- image throttle -->
<group if="$(arg save_rgb)">
<group if="$(arg save_depth)">
Expand Down Expand Up @@ -135,6 +140,8 @@
respawn="$(arg respawn)">
<remap from="~input" to="rgb/$(arg rgb_topic)$(arg rgb_suffix)" />
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
enable_monitor: $(arg enable_monitor)
monitor_topic: /$(arg camera_ns)/$(arg rgb_ns)/$(arg rgb_topic)
vital_check: $(arg vital_check)
Expand All @@ -147,6 +154,8 @@
respawn="$(arg respawn)">
<remap from="~input" to="rgb/$(arg camera_info_topic)" />
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
enable_monitor: $(arg enable_monitor)
monitor_topic: /$(arg camera_ns)/$(arg rgb_ns)/$(arg rgb_topic)
vital_check: $(arg vital_check)
Expand All @@ -161,6 +170,8 @@
respawn="$(arg respawn)">
<remap from="~input" to="depth/$(arg depth_topic)$(arg depth_suffix)" />
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
enable_monitor: $(arg enable_monitor)
monitor_topic: /$(arg camera_ns)/$(arg depth_ns)/$(arg depth_topic)
vital_check: $(arg vital_check)
Expand All @@ -173,6 +184,8 @@
respawn="$(arg respawn)">
<remap from="~input" to="depth/$(arg camera_info_topic)" />
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
enable_monitor: $(arg enable_monitor)
monitor_topic: /$(arg camera_ns)/$(arg depth_ns)/$(arg depth_topic)
vital_check: $(arg vital_check)
Expand All @@ -187,6 +200,8 @@
respawn="$(arg respawn)"
if="$(arg save_tf)">
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
update_rate: $(arg log_rate)
</rosparam>
</node>
Expand All @@ -199,6 +214,8 @@
respawn="$(arg respawn)">
<remap from="~input" to="/$(arg joint_states_topic)" />
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
periodic_rate: $(arg log_rate)
</rosparam>
</node>
Expand All @@ -208,6 +225,8 @@
respawn="$(arg respawn)">
<remap from="~input" to="joint_states_throttle/output" />
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
enable_monitor: $(arg enable_monitor)
monitor_topic: /$(arg joint_states_topic)
vital_check: $(arg vital_check)
Expand All @@ -221,6 +240,8 @@
machine="$(arg machine)"
respawn="$(arg respawn)">
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
topics:
- /server_name/smach/container_init
- /server_name/smach/container_status
Expand All @@ -234,6 +255,8 @@
machine="$(arg machine)"
respawn="$(arg respawn)">
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
topics:
- /Tablet/voice
</rosparam>
Expand Down Expand Up @@ -288,6 +311,8 @@
machine="$(arg machine)"
respawn="$(arg respawn)">
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
update_rate: $(arg log_rate)
map_frame: $(arg map_frame_id)
robot_frame: $(arg base_frame_id)
Expand All @@ -301,6 +326,8 @@
machine="$(arg machine)"
respawn="$(arg respawn)">
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
map_frame: $(arg map_frame_id)
robot_frame: $(arg base_frame_id)
</rosparam>
Expand All @@ -311,7 +338,12 @@
name="action_logger"
pkg="jsk_robot_startup" type="action_logger.py"
machine="$(arg machine)"
respawn="$(arg respawn)" />
respawn="$(arg respawn)">
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
</rosparam>
</node>

<!-- app manager -->
<node if="$(arg save_app)"
Expand All @@ -320,6 +352,8 @@
machine="$(arg machine)"
respawn="$(arg respawn)">
<rosparam subst_value="true">
database: $(arg database)
collection: $(arg collection)
subst_param: true
topics:
- /${param /robot/name}/app_list
Expand Down
10 changes: 9 additions & 1 deletion jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
<arg name="replicator_dump_path" default="/tmp/replicator_dumps" />
<arg name="replicator_param_path"
default="$(find jsk_robot_startup)/lifelog/mongodb_replication_params.yaml" />
<arg name="extra_collections" default="" />
<arg name="replicate_on_write" default="false"/>

<arg name="test_mode" default="false" />

Expand All @@ -18,9 +20,15 @@
<!-- Replication -->
<group if="$(arg replicate)">
<rosparam command="load" file="$(arg replicator_param_path)" />

<node name="replication_client"
pkg="jsk_robot_startup" type="periodic_replicator_client.py"
output="screen" machine="$(arg machine)"/>
output="screen" machine="$(arg machine)">
<rosparam subst_value="true" if="$(eval arg('extra_collections') != '')">
extra_collections: $(arg extra_collections)
replicate_on_write: $(arg replicate_on_write)
</rosparam>
</node>
</group>

<!-- MongoDB -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,10 @@ class ActionLogger(LoggerBase):
subscribers = {} # topicname:subscriber

def __init__(self):
LoggerBase.__init__(self)
db_name = rospy.get_param('~database', 'jsk_robot_lifelog')
col_name = rospy.get_param('~collection', None)

super(ActionLogger, self).__init__(db_name=db_name, col_name=col_name)

self.queue_size = rospy.get_param("~queue_size", 30)
self.action_regex = re.compile(".*Action(Result|Goal|Feedback)$")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,11 @@ def diff_pose(p1, p2):

class BaseTrajectoryLogger(LoggerBase):
def __init__(self):
LoggerBase.__init__(self)
db_name = rospy.get_param('~database', 'jsk_robot_lifelog')
col_name = rospy.get_param('~collection', None)

super(BaseTrajectoryLogger, self).__init__(db_name=db_name, col_name=col_name)

self.update_rate = rospy.get_param("~update_rate", 1.0)
self.use_amcl = rospy.get_param("~use_amcl", True)
self.persistent = rospy.get_param("~persistent", True)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ def __init__(self, db_name='jsk_robot_lifelog', col_name=None, ensure_index=True
super(LoggerBase, self).__init__()
self.db_name = rospy.get_param('/robot/database','jsk_robot_lifelog')
try:
if col_name is None:
if col_name in [None, 'USE_DEFAULT_VALUE']:
self.col_name = rospy.get_param('/robot/name')
else:
self.col_name = col_name
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ def __init__(self, argv=None):
self.queue_size = rospy.get_param("~queue_size", 1)
self.update_rate = rospy.get_param("~update_rate", 1.0)
subst_param = rospy.get_param("~subst_param", False)
database = rospy.get_param("~database", 'jsk_robot_lifelog')
collection = rospy.get_param("~collection", None)
else:
args = self.parse_args(argv)
Expand All @@ -28,6 +29,7 @@ def __init__(self, argv=None):
self.queue_size = args.queue_size
self.update_rate = args.update_rate
subst_param = args.subst_param
database = args.database
collection = args.collection
self.subscribers = {}

Expand All @@ -42,7 +44,7 @@ def __init__(self, argv=None):
topics.append(str().join(splitted))
self.topics = topics

LoggerBase.__init__(self, col_name=collection)
LoggerBase.__init__(self, db_name=database, col_name=collection)

def parse_args(self, argv):
p = argparse.ArgumentParser()
Expand All @@ -57,6 +59,8 @@ def parse_args(self, argv):
help="Enable substring param (e,g, '$(param robot/name)/list')")
p.add_argument("-r", "--update-rate", type=float, default=1.0,
help="Update rate for checking topics")
p.add_argument("-d", "--database", type=str, default=None,
help="Database name to record data")
p.add_argument("-c", "--collection", type=str, default=None,
help="Collection name to record data")
return p.parse_args(argv)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,11 @@

class ObjectDetectionLogger(LoggerBase):
def __init__(self):
LoggerBase.__init__(self)
db_name = rospy.get_param('~database', 'jsk_robot_lifelog')
col_name = rospy.get_param('~collection', None)

super(ObjectDetectionLogger, self).__init__(db_name=db_name, col_name=col_name)

self.update_rate = rospy.get_param("~update_rate", 1.0)
self.map_frame = rospy.get_param('~map_frame', 'map')
self.robot_frame = rospy.get_param('~robot_frame', 'base_footprint')
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,10 @@

class TFLogger(LoggerBase):
def __init__(self):
LoggerBase.__init__(self)
db_name = rospy.get_param('~database', 'jsk_robot_lifelog')
col_name = rospy.get_param('~collection', None)

super(TFLogger, self).__init__(db_name=db_name, col_name=col_name)

self.tf_buffer = tf2_ros.Buffer()
self.tf_listener = tf2_ros.TransformListener(self.tf_buffer)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,21 @@ namespace jsk_robot_startup
jsk_topic_tools::StealthRelay::onInit();

// settings for database
nh_->param<std::string>("/robot/database", db_name_, "jsk_robot_lifelog");
nh_->param<std::string>("/robot/name", col_name_, std::string());
if (ros::param::has(pnh_->resolveName("database")))
{
pnh_->param<std::string>("database", db_name_, "jsk_robot_lifelog");
}
else
{
pnh_->param<std::string>("/robot/database", db_name_, "jsk_robot_lifelog");
}

pnh_->param<std::string>("collection", col_name_, std::string());
if (col_name_.empty() || col_name_=="USE_DEFAULT_VALUE")
{
pnh_->param<std::string>("/robot/name", col_name_, std::string());
}

if (col_name_.empty())
{
NODELET_FATAL_STREAM("Please specify param 'robot/name' (e.g. pr1012, olive)");
Expand Down Expand Up @@ -123,7 +136,7 @@ namespace jsk_robot_startup

// The message store object is initialized here, since the object waits for connection
// until the connection to the server is established.
msg_store_.reset(new mongodb_store::MessageStoreProxy(*nh_, col_name_, db_name_));
msg_store_.reset(new mongodb_store::MessageStoreProxy(*pnh_, col_name_, db_name_));
initialized_ = true;

// After message store object is initialized, this thread is re-used for
Expand Down