Not sure if I understand your question correctly, but what you can do via ROS is to use a message_filter::Syncronizer templated on an ApproximateTime sync policy. I do this for the individual topics of one kinect, but you could of course extend it to also subscribe to the topics of the second kinect. My code is as follows:
Header Stuff:
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image,sensor_msgs::Image, sensor_msgs::PointCloud2> MySyncPolicy;
message_filters::Subscriber<sensor_msgs::Image> visual_sub_ ;
message_filters::Subscriber<sensor_msgs::Image> depth_sub_;
message_filters::Subscriber<sensor_msgs::PointCloud2> cloud_sub_;
message_filters::Synchronizer<MySyncPolicy> sync_;
Constructor
ClassName::ClassName(ros::NodeHandle nh,
const char* visual_topic,
const char* depth_topic, const char* cloud_topic,
const char* detector_type, const char* extractor_type)
: visual_sub_ (nh, visual_topic, global_subscriber_queue_size),
depth_sub_(nh, depth_topic, global_subscriber_queue_size),
cloud_sub_(nh, cloud_topic, global_subscriber_queue_size),
sync_(MySyncPolicy(global_subscriber_queue_size), visual_sub_, depth_sub_, cloud_sub_),
{
sync_.registerCallback(boost::bind(&ClassName::callback, this, _1, _2, _3));
}
I hope this snippet is complete.
For synchrounous triggering of two kinects, I don't think you can achieve that through ROS itself. You would need to dig into the cam driver AFAIK.