@@ -126,22 +126,22 @@ void CerebellumNode::ConfigureArmHooks()
RCLCPP_INFO ( this - > get_logger ( ) , " %.6f " , static_cast < double > ( val ) ) ;
}
goal . body_id = ( tls_arm_body_id = = arm : : LEFT_ARM | |
tls_arm_body_id = = arm : : RIGHT_ARM) ? tls_arm_body_id : arm : : LEFT_ARM ;
goal . body_id = ( tls_arm_body_id = = LEFT_ARM | |
tls_arm_body_id = = RIGHT_ARM ) ? tls_arm_body_id : LEFT_ARM ;
goal . data_type = arm : : ARM_COMMAND_TYPE_POSE_DIRECT_MOVE;
goal . data_type = ARM_COMMAND_TYPE_POSE_DIRECT_MOVE ;
goal . command_id = + + command_id_ ;
if ( goal . data_length = = 14 & & goal . data_array . size ( ) = = 14 ) {
if ( goal . body_id = = arm : : LEFT_ARM) {
if ( goal . body_id = = LEFT_ARM ) {
goal . data_array = { goal . data_array [ 0 ] , goal . data_array [ 1 ] , goal . data_array [ 2 ] ,
goal . data_array [ 3 ] , goal . data_array [ 4 ] , goal . data_array [ 5 ] , goal . data_array [ 6 ] } ;
} else if ( goal . body_id = = arm : : RIGHT_ARM) {
} else if ( goal . body_id = = RIGHT_ARM ) {
goal . data_array = { goal . data_array [ 7 ] , goal . data_array [ 8 ] , goal . data_array [ 9 ] ,
goal . data_array [ 10 ] , goal . data_array [ 11 ] , goal . data_array [ 12 ] , goal . data_array [ 13 ] } ;
}
}
goal . data_length = arm : : POSE_DIMENSION;
goal . data_length = POSE_DIMENSION ;
goal . frame_time_stamp = this - > get_clock ( ) - > now ( ) . nanoseconds ( ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] Control params: body_id=%d, data_type=%d, data_length=%d, command_id=%ld, frame_time_stamp=%ld, data_array=[%.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f] " ,
@@ -155,31 +155,31 @@ void CerebellumNode::ConfigureArmHooks()
ActionClientRegistry : : GoalHandle < interfaces : : action : : Arm > : : SharedPtr ,
const std : : shared_ptr < const interfaces : : action : : Arm : : Feedback > & feedback ) {
if ( ! feedback ) {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] feedback 为空 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] feedback is empty " , skill_name . c_str ( ) ) ;
return ;
}
( void ) feedback ;
//TODO :
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] command_id: %ld, current progress: %d " ,
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] command_id: %ld, current progress: %d " ,
skill_name . c_str ( ) , feedback - > command_id , feedback - > int_lenth ) ;
} ;
hooks . on_result = [ this ] (
const std : : string & skill_name ,
const ActionClientRegistry : : GoalHandle < interfaces : : action : : Arm > : : WrappedResult & res ) {
const bool success = ( res . code = = rclcpp_action : : ResultCode : : SUCCEEDED & & res . result & & res . result - > result = = arm : : OK) ;
const std : : string message = res . result ? std : : string ( " action end " ) : std : : string ( " 无返回信息 " ) ;
const bool success = ( res . code = = rclcpp_action : : ResultCode : : SUCCEEDED & & res . result & & res . result - > result = = OK ) ;
const std : : string message = res . result ? std : : string ( " action end " ) : std : : string ( " No return information " ) ;
geometry_msgs : : msg : : Pose pose = res . result - > pose ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] 最终位置 : %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f " ,
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] Final position : %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f " ,
skill_name . c_str ( ) , pose . position . x , pose . position . y , pose . position . z , pose . orientation . x , pose . orientation . y , pose . orientation . z , pose . orientation . w ) ;
if ( success ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] command_id %ld 完成 : %s " , skill_name . c_str ( ) , res . result - > command_id , message . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] command_id %ld completed : %s " , skill_name . c_str ( ) , res . result - > command_id , message . c_str ( ) ) ;
} else if ( res . code = = rclcpp_action : : ResultCode : : CANCELED ) {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] 被取消 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] was cancelled " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] 失败 (code=%d): %s " ,
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] failed (code=%d): %s " ,
skill_name . c_str ( ) , static_cast < int > ( res . code ) , message . c_str ( ) ) ;
}
} ;
@@ -187,9 +187,9 @@ void CerebellumNode::ConfigureArmHooks()
const std : : string & skill_name ,
const std : : shared_ptr < ActionClientRegistry : : GoalHandle < interfaces : : action : : Arm > > & handle ) {
if ( static_cast < bool > ( handle ) ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal 已被服务器接收 " , skill_name . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal has been accepted by server " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal 被服务器拒绝 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal was rejected by server " , skill_name . c_str ( ) ) ;
}
} ;
skill_manager_ - > configure_action_hooks < interfaces : : action : : Arm > ( " Arm " , std : : move ( hooks ) ) ;
@@ -212,7 +212,7 @@ void CerebellumNode::ConfigureHandControlHooks()
this - > declare_parameter < std : : vector < double > > ( param , { 0.0 , 0.0 , 0.0 } ) ;
}
const auto values = this - > get_parameter ( param ) . as_double_array ( ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] 目标参数 size=%zu " , skill_name . c_str ( ) , values . size ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] Target parameters size=%zu " , skill_name . c_str ( ) , values . size ( ) ) ;
( void ) values ;
goal . mode = 1 ;
return goal ;
@@ -230,13 +230,13 @@ void CerebellumNode::ConfigureHandControlHooks()
const std : : string & skill_name ,
const ActionClientRegistry : : GoalHandle < interfaces : : action : : HandControl > : : WrappedResult & res ) {
const bool success = res . code = = rclcpp_action : : ResultCode : : SUCCEEDED & & res . result & & res . result - > success ;
const std : : string message = res . result ? res . result - > message : std : : string ( " 无返回信息 " ) ;
const std : : string message = res . result ? res . result - > message : std : : string ( " No return information " ) ;
if ( success ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] 成功 : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] Success : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
} else if ( res . code = = rclcpp_action : : ResultCode : : CANCELED ) {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] 被取消 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] was cancelled " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] 失败 (code=%d): %s " ,
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] failed (code=%d): %s " ,
skill_name . c_str ( ) , static_cast < int > ( res . code ) , message . c_str ( ) ) ;
}
} ;
@@ -244,9 +244,9 @@ void CerebellumNode::ConfigureHandControlHooks()
const std : : string & skill_name ,
const std : : shared_ptr < ActionClientRegistry : : GoalHandle < interfaces : : action : : HandControl > > & handle ) {
if ( static_cast < bool > ( handle ) ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal 已被服务器接收 " , skill_name . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal has been accepted by server " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal 被服务器拒绝 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal was rejected by server " , skill_name . c_str ( ) ) ;
}
} ;
skill_manager_ - > configure_action_hooks < interfaces : : action : : HandControl > ( " HandControl " , std : : move ( hooks ) ) ;
@@ -265,7 +265,8 @@ void CerebellumNode::ConfigureMoveWaistHooks()
// Plan A: load per-call YAML payload into goal if present
( void ) TryParseCallPayload < interfaces : : action : : MoveWaist : : Goal > ( skill_name , goal ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] move_pitch_degree: %f, move_yaw_degree: %f " , skill_name . c_str ( ) , goal . move_pitch_degree , goal . move_yaw_degree ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] move_pitch_degree: %f, move_yaw_degree: %f " ,
skill_name . c_str ( ) , goal . move_pitch_degree , goal . move_yaw_degree ) ;
return goal ;
} ;
@@ -281,13 +282,13 @@ void CerebellumNode::ConfigureMoveWaistHooks()
const std : : string & skill_name ,
const ActionClientRegistry : : GoalHandle < interfaces : : action : : MoveWaist > : : WrappedResult & res ) {
const bool success = res . code = = rclcpp_action : : ResultCode : : SUCCEEDED & & res . result & & res . result - > success ;
const std : : string message = res . result ? res . result - > message : std : : string ( " 无返回信息 " ) ;
const std : : string message = res . result ? res . result - > message : std : : string ( " No return information " ) ;
if ( success ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] 成功 : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] Success : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
} else if ( res . code = = rclcpp_action : : ResultCode : : CANCELED ) {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] 被取消 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] was cancelled " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] 失败 (code=%d): %s " ,
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] failed (code=%d): %s " ,
skill_name . c_str ( ) , static_cast < int > ( res . code ) , message . c_str ( ) ) ;
}
} ;
@@ -295,9 +296,9 @@ void CerebellumNode::ConfigureMoveWaistHooks()
const std : : string & skill_name ,
const std : : shared_ptr < ActionClientRegistry : : GoalHandle < interfaces : : action : : MoveWaist > > & handle ) {
if ( static_cast < bool > ( handle ) ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal 已被服务器接收 " , skill_name . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal has been accepted by server " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal 被服务器拒绝 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal was rejected by server " , skill_name . c_str ( ) ) ;
}
} ;
skill_manager_ - > configure_action_hooks < interfaces : : action : : MoveWaist > ( " MoveWaist " , std : : move ( hooks ) ) ;
@@ -328,13 +329,13 @@ void CerebellumNode::ConfigureMoveLegHooks()
const std : : string & skill_name ,
const ActionClientRegistry : : GoalHandle < interfaces : : action : : MoveLeg > : : WrappedResult & res ) {
const bool success = res . code = = rclcpp_action : : ResultCode : : SUCCEEDED & & res . result & & res . result - > success ;
const std : : string message = res . result ? res . result - > message : std : : string ( " 无返回信息 " ) ;
const std : : string message = res . result ? res . result - > message : std : : string ( " No return information " ) ;
if ( success ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] 成功 : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] Success : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
} else if ( res . code = = rclcpp_action : : ResultCode : : CANCELED ) {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] 被取消 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] was cancelled " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] 失败 (code=%d): %s " ,
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] failed (code=%d): %s " ,
skill_name . c_str ( ) , static_cast < int > ( res . code ) , message . c_str ( ) ) ;
}
} ;
@@ -342,9 +343,9 @@ void CerebellumNode::ConfigureMoveLegHooks()
const std : : string & skill_name ,
const std : : shared_ptr < ActionClientRegistry : : GoalHandle < interfaces : : action : : MoveLeg > > & handle ) {
if ( static_cast < bool > ( handle ) ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal 已被服务器接收 " , skill_name . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal has been accepted by server " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal 被服务器拒绝 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal was rejected by server " , skill_name . c_str ( ) ) ;
}
} ;
skill_manager_ - > configure_action_hooks < interfaces : : action : : MoveLeg > ( " MoveLeg " , std : : move ( hooks ) ) ;
@@ -377,13 +378,13 @@ void CerebellumNode::ConfigureMoveWheelHooks()
const std : : string & skill_name ,
const ActionClientRegistry : : GoalHandle < interfaces : : action : : MoveWheel > : : WrappedResult & res ) {
const bool success = res . code = = rclcpp_action : : ResultCode : : SUCCEEDED & & res . result & & res . result - > success ;
const std : : string message = res . result ? res . result - > message : std : : string ( " 无返回信息 " ) ;
const std : : string message = res . result ? res . result - > message : std : : string ( " No return information " ) ;
if ( success ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] 成功 : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] Success : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
} else if ( res . code = = rclcpp_action : : ResultCode : : CANCELED ) {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] 被取消 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] was cancelled " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] 失败 (code=%d): %s " ,
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] failed (code=%d): %s " ,
skill_name . c_str ( ) , static_cast < int > ( res . code ) , message . c_str ( ) ) ;
}
} ;
@@ -391,9 +392,9 @@ void CerebellumNode::ConfigureMoveWheelHooks()
const std : : string & skill_name ,
const std : : shared_ptr < ActionClientRegistry : : GoalHandle < interfaces : : action : : MoveWheel > > & handle ) {
if ( static_cast < bool > ( handle ) ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal 已被服务器接收 " , skill_name . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal has been accepted by server " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal 被服务器拒绝 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal was rejected by server " , skill_name . c_str ( ) ) ;
}
} ;
skill_manager_ - > configure_action_hooks < interfaces : : action : : MoveWheel > ( " MoveWheel " , std : : move ( hooks ) ) ;
@@ -426,13 +427,13 @@ void CerebellumNode::ConfigureMoveHomeHooks()
const std : : string & skill_name ,
const ActionClientRegistry : : GoalHandle < interfaces : : action : : MoveHome > : : WrappedResult & res ) {
const bool success = res . code = = rclcpp_action : : ResultCode : : SUCCEEDED & & res . result & & res . result - > success ;
const std : : string message = res . result ? res . result - > message : std : : string ( " 无返回信息 " ) ;
const std : : string message = res . result ? res . result - > message : std : : string ( " No return information " ) ;
if ( success ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] 成功 : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] Success : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
} else if ( res . code = = rclcpp_action : : ResultCode : : CANCELED ) {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] 被取消 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] was cancelled " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] 失败 (code=%d): %s " ,
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] failed (code=%d): %s " ,
skill_name . c_str ( ) , static_cast < int > ( res . code ) , message . c_str ( ) ) ;
}
} ;
@@ -440,9 +441,9 @@ void CerebellumNode::ConfigureMoveHomeHooks()
const std : : string & skill_name ,
const std : : shared_ptr < ActionClientRegistry : : GoalHandle < interfaces : : action : : MoveHome > > & handle ) {
if ( static_cast < bool > ( handle ) ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal 已被服务器接收 " , skill_name . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal has been accepted by server " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal 被服务器拒绝 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal was rejected by server " , skill_name . c_str ( ) ) ;
}
} ;
skill_manager_ - > configure_action_hooks < interfaces : : action : : MoveHome > ( " MoveHome " , std : : move ( hooks ) ) ;
@@ -455,7 +456,7 @@ void CerebellumNode::ConfigureMoveHomeHooks()
void CerebellumNode : : ConfigureActionHooks ( )
{
if ( ! skill_manager_ ) {
RCLCPP_WARN ( this - > get_logger ( ) , " SkillManager 不可用,跳过动作钩子配置 " ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " SkillManager unavailable, skipping action hook configuration " ) ;
return ;
}
ConfigureArmHooks ( ) ;
@@ -517,7 +518,6 @@ void CerebellumNode::ConfigureVisionObjectRecognitionHooks()
for ( size_t i = 0 ; i < resp - > objects . size ( ) ; + + i ) {
const auto & obj = resp - > objects [ i ] ;
//判断target_pose_的key是否等于obj.class_name, 如果相等, 将value存入target_pose_的PostStamped
if ( target_frame_ = = obj . class_name ) {
target_pose_ [ target_frame_ ] . header = resp - > header ;
target_pose_ [ target_frame_ ] . pose = obj . pose_list [ 0 ] ;
@@ -559,13 +559,13 @@ void CerebellumNode::ConfigureCameraTakePhotoHooks()
const std : : string & skill_name ,
const ActionClientRegistry : : GoalHandle < interfaces : : action : : CameraTakePhoto > : : WrappedResult & res ) {
const bool success = res . code = = rclcpp_action : : ResultCode : : SUCCEEDED & & res . result & & res . result - > success ;
const std : : string message = res . result ? res . result - > message : std : : string ( " 无返回信息 " ) ;
const std : : string message = res . result ? res . result - > message : std : : string ( " No return information " ) ;
if ( success ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] 成功 : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] Success : %s " , skill_name . c_str ( ) , message . c_str ( ) ) ;
} else if ( res . code = = rclcpp_action : : ResultCode : : CANCELED ) {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] 被取消 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] was cancelled " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] 失败 (code=%d): %s " ,
RCLCPP_ERROR ( this - > get_logger ( ) , " [%s] failed (code=%d): %s " ,
skill_name . c_str ( ) , static_cast < int > ( res . code ) , message . c_str ( ) ) ;
}
} ;
@@ -573,9 +573,9 @@ void CerebellumNode::ConfigureCameraTakePhotoHooks()
const std : : string & skill_name ,
const std : : shared_ptr < ActionClientRegistry : : GoalHandle < interfaces : : action : : CameraTakePhoto > > & handle ) {
if ( static_cast < bool > ( handle ) ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal 已被服务器接收 " , skill_name . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " [%s] goal has been accepted by server " , skill_name . c_str ( ) ) ;
} else {
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal 被服务器拒绝 " , skill_name . c_str ( ) ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " [%s] goal was rejected by server " , skill_name . c_str ( ) ) ;
}
} ;
skill_manager_ - > configure_action_hooks < interfaces : : action : : CameraTakePhoto > ( " CameraTakePhoto " , std : : move ( hooks ) ) ;
@@ -654,7 +654,7 @@ void CerebellumNode::ConfigureMapSaveHooks()
void CerebellumNode : : ConfigureServiceHooks ( )
{
if ( ! skill_manager_ ) {
RCLCPP_WARN ( this - > get_logger ( ) , " SkillManager 不可用,跳过服务钩子配置 " ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " SkillManager unavailable, skipping service hook configuration " ) ;
return ;
}
ConfigureVisionObjectRecognitionHooks ( ) ;
@@ -854,15 +854,15 @@ bool CerebellumNode::TransformPoseToArmFrame(
geometry_msgs : : msg : : PoseStamped & transformed ) const
{
if ( ! tf_buffer_ ) {
RCLCPP_ERROR ( this - > get_logger ( ) , " TF buffer 未初始化,无法转换目标点位 " ) ;
RCLCPP_ERROR ( this - > get_logger ( ) , " TF buffer not initialized, unable to transform target pose " ) ;
return false ;
}
if ( source . header . frame_id . empty ( ) ) {
RCLCPP_WARN ( this - > get_logger ( ) , " 目标姿态缺少来源坐标系,跳过转换 " ) ;
RCLCPP_WARN ( this - > get_logger ( ) , " Target pose missing source frame, skipping transformation " ) ;
return false ;
}
if ( source . header . frame_id = = arm_target_frame_ ) {
RCLCPP_INFO ( this - > get_logger ( ) , " 目标姿态已位于 %s 坐标系,跳过转换 " , arm_target_frame_ . c_str ( ) ) ;
RCLCPP_INFO ( this - > get_logger ( ) , " Target pose already in %s frame, skipping transformation " , arm_target_frame_ . c_str ( ) ) ;
transformed = source ;
return true ;
}
@@ -870,12 +870,12 @@ bool CerebellumNode::TransformPoseToArmFrame(
transformed = tf_buffer_ - > transform (
source , arm_target_frame_ , tf2 : : durationFromSec ( arm_transform_timeout_sec_ ) ) ;
RCLCPP_INFO (
this - > get_logger ( ) , " 目标姿态从 %s 转换至 %s" ,
this - > get_logger ( ) , " Target pose transformed from %s to %s" ,
source . header . frame_id . c_str ( ) , arm_target_frame_ . c_str ( ) ) ;
return true ;
} catch ( const tf2 : : TransformException & ex ) {
RCLCPP_ERROR (
this - > get_logger ( ) , " 转换目标姿态失败 : %s -> %s, 原因 : %s" ,
this - > get_logger ( ) , " Failed to transform target pose : %s -> %s, reason : %s" ,
source . header . frame_id . c_str ( ) , arm_target_frame_ . c_str ( ) , ex . what ( ) ) ;
}
return false ;
@@ -1115,62 +1115,9 @@ bool CerebellumNode::ExecuteActionSkill(
}
auto timeout = std : : chrono : : duration_cast < std : : chrono : : nanoseconds > (
std : : chrono : : duration < double > ( GetTimeoutForSkill ( skill ) ) ) ;
if ( skill = = " Arm " ) {
RCLCPP_INFO ( this - > get_logger ( ) , " [Arm] 并发发送两个 goal: body_id=1 与 body_id=0 " ) ;
std : : atomic < bool > finished1 { false } , finished2 { false } ;
bool ok1 = false , ok2 = false ;
std : : string d1 , d2 ;
auto worker = [ this , & ok_out = ok1 , & done_flag = finished1 , & d_out = d1 ,
skill , topic , timeout ] ( int body_id ) {
tls_arm_body_id = body_id ;
ok_out = brain : : dispatch_skill_action < 0 , brain : : SkillActionTypes > (
skill , topic , action_clients_ . get ( ) , this - > get_logger ( ) , timeout , d_out ) ;
done_flag . store ( true , std : : memory_order_release ) ;
} ;
std : : thread t1 ( worker , 1 ) ; // RIGHT_ARM=1
auto worker2 = [ this , & ok_out = ok2 , & done_flag = finished2 , & d_out = d2 ,
skill , topic , timeout ] ( int body_id ) {
tls_arm_body_id = body_id ;
ok_out = brain : : dispatch_skill_action < 0 , brain : : SkillActionTypes > (
skill , topic , action_clients_ . get ( ) , this - > get_logger ( ) , timeout , d_out ) ;
done_flag . store ( true , std : : memory_order_release ) ;
} ;
std : : thread t2 ( worker2 , 0 ) ; // LEFT_ARM=0
const auto start_steady = std : : chrono : : steady_clock : : now ( ) ;
const double timeout_sec = timeout . count ( ) / 1e9 ;
while ( ! ( finished1 . load ( std : : memory_order_acquire ) & & finished2 . load ( std : : memory_order_acquire ) ) ) {
auto now = std : : chrono : : steady_clock : : now ( ) ;
double elapsed = std : : chrono : : duration < double > ( now - start_steady ) . count ( ) ;
double phase = timeout_sec > 0.0 ? std : : min ( elapsed / timeout_sec , 0.99 ) : 0.0 ;
double sub_done = ( finished1 . load ( std : : memory_order_relaxed ) ? 1.0 : phase )
+ ( finished2 . load ( std : : memory_order_relaxed ) ? 1.0 : phase ) ;
double avg_phase = 0.5 * std : : min ( sub_done , 2.0 ) ;
float seq_progress =
( total_skills > 0 ) ? static_cast < float > ( ( index + avg_phase ) / total_skills ) : 0.f ;
PublishFeedbackStage ( goal_handle , " RUN " , skill , seq_progress , " " ) ;
std : : this_thread : : sleep_for ( std : : chrono : : milliseconds ( 200 ) ) ;
}
if ( t1 . joinable ( ) ) t1 . join ( ) ; //RIGHT ARM
if ( t2 . joinable ( ) ) t2 . join ( ) ; //LEFT ARM
if ( ! ok1 | | ! ok2 ) {
std : : ostringstream oss ;
if ( ! ok1 ) { oss < < " Arm(body_id=1) 失败 " ; if ( ! d1 . empty ( ) ) oss < < " : " < < d1 ; }
if ( ! ok2 ) { if ( ! oss . str ( ) . empty ( ) ) oss < < " ; " ; oss < < " Arm(body_id=0) 失败 " ; if ( ! d2 . empty ( ) ) oss < < " : " < < d2 ; }
detail = oss . str ( ) ;
return false ;
}
detail . clear ( ) ;
return true ;
}
// 其他动作按一次发送
return RunActionSkillWithProgress (
skill , topic , timeout , index , total_skills , goal_handle , detail ) ;
return ( skill = = " Arm " ) ?
ExecuteBilateralArmAction ( skill , topic , timeout , index , total_skills , goal_handle , detail ) :
RunActionSkillWithProgress ( skill , topic , timeout , index , total_skills , goal_handle , detail ) ;
}
/**
@@ -1217,12 +1164,98 @@ bool CerebellumNode::RunActionSkillWithProgress(
PublishFeedbackStage ( goal_handle , " RUN " , skill , seq_progress , " " ) ;
std : : this_thread : : sleep_for ( std : : chrono : : milliseconds ( 200 ) ) ;
}
if ( worker . joinable ( ) ) { worker . join ( ) ; }
if ( worker . joinable ( ) ) {
try {
worker . join ( ) ;
} catch ( const std : : exception & e ) {
RCLCPP_ERROR ( this - > get_logger ( ) , " Exception in worker thread join: %s " , e . what ( ) ) ;
}
}
detail = local_detail ;
if ( ! ok & & detail . empty ( ) ) { detail = " Unsupported action skill " ; }
return ok ;
}
/**
* @brief Execute bilateral arm actions concurrently.
*
* Launches two threads executing dispatch_skill_action for each arm while the main thread publishes
* RUN stage feedback at fixed intervals until both actions complete.
* @param skill Skill name.
* @param topic Action topic/client key.
* @param timeout Action timeout.
* @param index Skill's zero-based index within the sequence.
* @param total_skills Total number of skills in the sequence.
* @param goal_handle ExecuteBtAction goal handle for feedback publication.
* @param detail [out] Detailed status or error information.
* @return true if both actions report success; false otherwise.
*/
bool CerebellumNode : : ExecuteBilateralArmAction (
const std : : string & skill ,
const std : : string & topic ,
std : : chrono : : nanoseconds timeout ,
int index ,
int total_skills ,
const std : : shared_ptr < rclcpp_action : : ServerGoalHandle < interfaces : : action : : ExecuteBtAction > > & goal_handle ,
std : : string & detail )
{
RCLCPP_INFO ( this - > get_logger ( ) , " [Arm] send two goals: body_id=1 and body_id=0 " ) ;
std : : atomic < bool > finished1 { false } , finished2 { false } ;
bool ok1 = false , ok2 = false ;
std : : string d1 , d2 ;
auto worker = [ this , & ok_out = ok1 , & done_flag = finished1 , & d_out = d1 ,
skill , topic , timeout ] ( int body_id ) {
tls_arm_body_id = body_id ;
ok_out = brain : : dispatch_skill_action < 0 , brain : : SkillActionTypes > (
skill , topic , action_clients_ . get ( ) , this - > get_logger ( ) , timeout , d_out ) ;
done_flag . store ( true , std : : memory_order_release ) ;
} ;
std : : thread t1 ( worker , RIGHT_ARM ) ; // RIGHT_ARM=1
auto worker2 = [ this , & ok_out = ok2 , & done_flag = finished2 , & d_out = d2 ,
skill , topic , timeout ] ( int body_id ) {
tls_arm_body_id = body_id ;
ok_out = brain : : dispatch_skill_action < 0 , brain : : SkillActionTypes > (
skill , topic , action_clients_ . get ( ) , this - > get_logger ( ) , timeout , d_out ) ;
done_flag . store ( true , std : : memory_order_release ) ;
} ;
std : : thread t2 ( worker2 , LEFT_ARM ) ; // LEFT_ARM=0
const auto start_steady = std : : chrono : : steady_clock : : now ( ) ;
while ( ! ( finished1 . load ( std : : memory_order_acquire ) & & finished2 . load ( std : : memory_order_acquire ) ) ) {
double elapsed_ms = std : : chrono : : duration_cast < std : : chrono : : milliseconds > ( std : : chrono : : steady_clock : : now ( ) - start_steady ) . count ( ) ;
PublishFeedbackStage ( goal_handle , " RUN " , skill , elapsed_ms , " " ) ;
std : : this_thread : : sleep_for ( std : : chrono : : milliseconds ( 500 ) ) ;
}
if ( t1 . joinable ( ) ) {
try {
t1 . join ( ) ;
} catch ( const std : : exception & e ) {
RCLCPP_ERROR ( this - > get_logger ( ) , " Exception in Arm thread 1 join: %s " , e . what ( ) ) ;
}
}
if ( t2 . joinable ( ) ) {
try {
t2 . join ( ) ;
} catch ( const std : : exception & e ) {
RCLCPP_ERROR ( this - > get_logger ( ) , " Exception in Arm thread 2 join: %s " , e . what ( ) ) ;
}
}
if ( ! ok1 | | ! ok2 ) {
std : : ostringstream oss ;
if ( ! ok1 ) { oss < < " Arm(body_id=1) failed " ; if ( ! d1 . empty ( ) ) oss < < " : " < < d1 ; }
if ( ! ok2 ) { if ( ! oss . str ( ) . empty ( ) ) oss < < " ; " ; oss < < " Arm(body_id=0) failed " ; if ( ! d2 . empty ( ) ) oss < < " : " < < d2 ; }
detail = oss . str ( ) ;
return false ;
}
detail . clear ( ) ;
return true ;
}
/**
* @brief Execute a supported service-based skill (currently VisionObjectRecognition).
*