3 #include <visp/vpRobotBiclops.h> 8 #include <geometry_msgs/TwistStamped.h> 9 #include <geometry_msgs/Pose.h> 10 #include <geometry_msgs/PoseStamped.h> 11 #include <nav_msgs/Odometry.h> 20 #ifdef VISP_HAVE_BICLOPS 30 void setJointVel(
const geometry_msgs::TwistConstPtr &);
31 void setJointPos(
const geometry_msgs::PoseConstPtr &);
57 vpHomogeneousMatrix
wMc;
104 robot =
new vpRobotBiclops(
"/usr/share/BiclopsDefault.cfg");
105 robot->setDenavitHartenbergModel(vpBiclops::DH2);
107 vpColVector qinit(2);
109 robot->setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
110 robot->setPositioningVelocity(40);
111 robot->setPosition(vpRobot::ARTICULAR_FRAME, qinit);
113 robot->setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
131 robot->getPosition(vpRobot::ARTICULAR_FRAME,
q);
157 qdot[1] = msg->angular.x;
158 qdot[0] = msg->angular.y;
161 ROS_INFO(
"Biclops new joint vel at %f s: [%0.2f %0.2f] rad/s",
164 robot->setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
165 robot->setVelocity(vpRobot::ARTICULAR_FRAME, qdot);
174 qdes[0] = msg->orientation.x;
175 qdes[1] = msg->orientation.y;
177 ROS_INFO(
"Biclops new joint pos at %f s: [%0.2f %0.2f] rad/s",
180 robot->setRobotState(vpRobot::STATE_POSITION_CONTROL);
181 robot->setPosition(vpRobot::ARTICULAR_FRAME, qdes);
184 #endif // #ifdef VISP_HAVE_BICLOPS 187 int main(
int argc,
char** argv )
189 #ifdef VISP_HAVE_BICLOPS 195 if( node->
setup() != 0 )
197 printf(
"Biclops setup failed... \n" );
205 printf(
"\nQuitting... \n" );
207 printf(
"This node is node available since ViSP was \nnot build with Biclops robot support...\n");
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
geometry_msgs::TransformStamped odom_trans
geometry_msgs::PoseStamped position
std::string frame_id_base_link
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setJointVel(const geometry_msgs::TwistConstPtr &)
virtual ~RosBiclopsNode()
RosBiclopsNode(ros::NodeHandle n)
ros::Subscriber cmd_jointpos_sub
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::TransformBroadcaster odom_broadcaster
std::string frame_id_odom
ros::Subscriber cmd_jointvel_sub
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)
void setJointPos(const geometry_msgs::PoseConstPtr &)