2 #include <semio_msgs_ros/AttentionTargets.h> 58 _attention_targets_pub( nh_rel.advertise<_AttentionTargetsMsg>(
"attention_targets", 10 ) ),
59 _humanoid_source_ptr( humanoid_source_ptr ),
60 _humanoid_sink_ptr( humanoid_sink_ptr ),
61 _is_virtual_source( std::dynamic_pointer_cast<
semio::HumanoidSourceVirtual>( _humanoid_source_ptr ) )
63 size_t const cols( _nh_rel.param<
int>(
"cols", 13 ) );
64 size_t const rows( _nh_rel.param<
int>(
"rows", 7 ) );
65 double const horizontal_spacing( _nh_rel.param<
double>(
"h_spacing", 15 ) );
66 double const vertical_spacing( _nh_rel.param<
double>(
"v_spacing", 15 ) );
67 double const radius( _nh_rel.param<
double>(
"radius", 2 ) );
69 std::cout <<
"using " << cols <<
"x" << rows <<
" @ " << horizontal_spacing <<
"x" << vertical_spacing << std::endl;
70 Eigen::Vector3d
const center( radius, 0, 0 );
72 double const yaw_range( horizontal_spacing * static_cast<double>( cols - 1 ) / 2.0 );
73 double const pitch_range( vertical_spacing * static_cast<double>( rows - 1 ) / 2.0 );
75 for(
size_t col = 0; col < cols; ++col )
77 for(
size_t row = 0; row < rows; ++row )
79 double const yaw( yaw_range - static_cast<double>( col ) * horizontal_spacing );
80 double const pitch( -pitch_range + static_cast<double>( row ) * vertical_spacing );
82 std::stringstream name_stream;
83 name_stream << ( col * rows + row );
84 _attention_targets.emplace(
88 Eigen::Translation3d( center ) *
89 Eigen::Quaterniond( Eigen::AngleAxisd( M_PI, Eigen::Vector3d::UnitZ() ) )
93 Eigen::AngleAxisd( yaw * M_PI/180, Eigen::Vector3d::UnitZ() ) *
94 Eigen::AngleAxisd( pitch * M_PI/180, Eigen::Vector3d::UnitY() )
96 Eigen::Translation3d( radius, 0, 0 )
103 if( _is_virtual_source )
105 _test_poses.push_back( std::move(
TestPose{ Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 180 ), Eigen::Vector3d( 2, 0, 0 ) } ) );
106 _test_poses.push_back( std::move(
TestPose{ Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 180 + 45 ), Eigen::Vector3d( 2, 0, 0 ) } ) );
107 _test_poses.push_back( std::move(
TestPose{ Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 180 - 45 ), Eigen::Vector3d( 2, 0, 0 ) } ) );
108 _test_poses.push_back( std::move(
TestPose{ Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 180 + 90 ), Eigen::Vector3d( 2, 0, 0 ) } ) );
109 _test_poses.push_back( std::move(
TestPose{ Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 180 - 90 ), Eigen::Vector3d( 2, 0, 0 ) } ) );
110 _test_poses.push_back( std::move(
TestPose{ Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 180 ), Eigen::Vector3d( 2, -2, 0 ) } ) );
111 _test_poses.push_back( std::move(
TestPose{ Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 0 ), Eigen::Vector3d( 0, 0, 180 ), Eigen::Vector3d( 2, 2, 0 ) } ) );
113 for(
double const & torso_yaw : { 90, 45, 0, -45, -90 } )
115 for(
double const & neck_yaw : { 45, 30, 15, 0, -15, -30, -45 } )
117 for(
double const & head_yaw : { 45, 30, 15, 0, -15, -30, -45 } )
119 _test_poses.push_back( std::move(
TestPose{ Eigen::Vector3d( 0, 0, head_yaw ), Eigen::Vector3d( 0, 0, neck_yaw ), Eigen::Vector3d( 0, 0, 180 + torso_yaw ), Eigen::Vector3d( 1, 0, 0 ) } ) );
130 _humanoid_sink_ptr->publish( _humanoid_source_ptr->update() );
134 _AttentionTargetsMsg attention_targets_msg;
136 attention_targets_msg.targets.reserve( _attention_targets.size() );
138 for(
auto const & attention_target : _attention_targets )
140 _AttentionTargetMsg attention_target_msg;
142 attention_target_msg.name = attention_target.name_;
143 attention_target_msg.position.x = attention_target.position_.x();
144 attention_target_msg.position.y = attention_target.position_.y();
145 attention_target_msg.position.z = attention_target.position_.z();
147 attention_targets_msg.targets.push_back( std::move( attention_target_msg ) );
152 _attention_targets_pub.publish( attention_targets_msg );
163 if( _is_virtual_source )
165 ros::Duration sleep_interval( 0.5 );
166 size_t test_pose_idx = 1;
167 for(
auto const & test_pose : _test_poses )
169 if( !ros::ok() )
break;
173 std::cout <<
"pose " << test_pose_idx <<
"/" << _test_poses.size() << std::endl;
176 auto humanoid_source_virtual_ptr( std::dynamic_pointer_cast<semio::HumanoidSourceVirtual>( _humanoid_source_ptr ) );
177 humanoid_source_virtual_ptr->setPosition( test_pose.position );
178 humanoid_source_virtual_ptr->setOrientation(
180 Eigen::AngleAxisd( test_pose.head_rotation.x() * M_PI/180, Eigen::Vector3d::UnitX() ) *
181 Eigen::AngleAxisd( test_pose.head_rotation.y() * M_PI/180, Eigen::Vector3d::UnitY() ) *
182 Eigen::AngleAxisd( test_pose.head_rotation.z() * M_PI/180, Eigen::Vector3d::UnitZ() ) );
183 humanoid_source_virtual_ptr->setOrientation(
185 Eigen::AngleAxisd( test_pose.neck_rotation.x() * M_PI/180, Eigen::Vector3d::UnitX() ) *
186 Eigen::AngleAxisd( test_pose.neck_rotation.y() * M_PI/180, Eigen::Vector3d::UnitY() ) *
187 Eigen::AngleAxisd( test_pose.neck_rotation.z() * M_PI/180, Eigen::Vector3d::UnitZ() ) );
188 humanoid_source_virtual_ptr->setOrientation(
190 Eigen::AngleAxisd( test_pose.torso_rotation.x() * M_PI/180, Eigen::Vector3d::UnitX() ) *
191 Eigen::AngleAxisd( test_pose.torso_rotation.y() * M_PI/180, Eigen::Vector3d::UnitY() ) *
192 Eigen::AngleAxisd( test_pose.torso_rotation.z() * M_PI/180, Eigen::Vector3d::UnitZ() ) );
196 sleep_interval.sleep();
202 ros::Rate loop_rate( 30 );
216 int main(
int argc,
char ** argv )
218 ros::init( argc, argv,
"example_attention_targets_node" );
220 ros::NodeHandle nh_rel(
"~" );
230 example_attention_targets_node.
spin();
semio_msgs_ros::AttentionTargets _AttentionTargetsMsg
ROS message for a vector of attention targets.
decltype(std::make_shared< HumanoidSink >()) typedef Ptr
std::set< AttentionTarget > AttentionTargetArray
Example node demonstrating how to publish targets for attention recognition.
Eigen::Vector3d neck_rotation
Rotation of the neck joint for the test pose (relative to global frame)
Utility class to simplify the creation of semio::HumanoidSink instances.
bool _is_virtual_source
Whether the input source is a semio::HumanoidSourceVirtual.
void publishData()
Publish all relevant data.
ExampleAttentionTargetsNode(ros::NodeHandle &nh_rel, semio::HumanoidSource::Ptr humanoid_source_ptr, semio::HumanoidSink::Ptr humanoid_sink_ptr)
std::vector< TestPose > _test_poses
The list of test poses to use if _is_virtual_source == true.
semio::AttentionTargetArray _attention_targets
The list of attention targets to publish.
ros::NodeHandle & _nh_rel
NodeHandle used to interface with ROS.
decltype(std::make_shared< HumanoidSource >()) typedef Ptr
semio::HumanoidSink::Ptr _humanoid_sink_ptr
Pointer to the output sink for humanoids.
Eigen::Vector3d position
Position of the torso joint for the test pose (relative to global frame)
int main(int argc, char **argv)
Utility class to simplify the creation of semio::HumanoidSource instances.
semio::HumanoidSource::Ptr _humanoid_source_ptr
Pointer to the input source for humanoids.
Eigen::Vector3d torso_rotation
Rotation of the torso joint for the test pose (relative to global frame)
HumanoidSource::Ptr getHumanoidSource(std::string const &source="param")
Create a semio::HumanoidSource.
ros::Publisher _attention_targets_pub
Publisher for our attention targets.
Eigen::Vector3d head_rotation
Rotation of the head joint for the test pose (relative to global frame)
Stores a partial pose (head/neck/torso rotations and the torso position) of a virtual humanoid...
HumanoidSink::Ptr getHumanoidSink(std::string const &sink="param")
Create a semio::HumanoidSink.
semio_msgs_ros::AttentionTarget _AttentionTargetMsg
ROS message for a single attention target.