紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
ros2 foxy move_group->getCurrentJointValues()获取失败
-
我查看过源码,该错误是从CurrentStateMonitor::waitForCurrentState发出,真正原因是current_state_time_没有更新,而current_state_time_是从joint_states回调中更新,但我的joint_states是有在更新的
-
@mu 直接在源码上加些打印之类的debug下,应该 很快可以找出来
-
@小鱼 我打印了,在启动构造的时候它是可以正确的获取到,构造完后调用服务的时候就无法获取到了
这里最后可以正常获取,当我调用home_teleop_server_时就无法获取了。。。
ElfinTeleopAPI::ElfinTeleopAPI(const rclcpp::Node::SharedPtr& node,moveit::planning_interface::MoveGroupInterface *group, std::string action_name, planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor): group_(group),planning_scene_monitor_(planning_scene_monitor), teleop_nh_(node) { home_teleop_server_=teleop_nh_->create_service<std_srvs::srv::SetBool>("home_teleop", std::bind(&ElfinTeleopAPI::homeTeleop_cb,this,std::placeholders::_1,std::placeholders::_2)); end_link_=group_->getEndEffectorLink(); reference_link_=group_->getPlanningFrame(); default_tip_link_=group_->getEndEffectorLink(); root_link_=group_->getPlanningFrame(); std::cout<<"----------teleop_api-----------"<<std::endl; std::cout<<end_link_<<reference_link_<<default_tip_link_<<root_link_<<std::endl; std::cout<<group_->getCurrentJointValues().size()<<std::endl; std::cout<<group_->getCurrentPose().pose.position.x<<std::endl; std::cout<<"---------------"<<std::endl; }
bool ElfinTeleopAPI::homeTeleop_cb(std_srvs::srv::SetBool::Request::SharedPtr req, std_srvs::srv::SetBool::Response::SharedPtr resp) { moveit::core::RobotStatePtr current_state=group_->getCurrentState(); std::cout<<"----home_callback-------"<<std::endl; std::vector<double> position_current=group_->getCurrentJointValues(); std::cout<<position_current.size()<<goal_.trajectory.joint_names.size()<<std::endl; std::cout<<group_->getCurrentPose().pose.position.x<<std::endl; ........ }
-
-
@小鱼 是的,启动节点在构造中打印一切正常,启动完成后我调用服务,它在服务回调中就无法获取了。。。